This document describes every function and constant available inside a Lua program running on Megahub. All programs run under Lua 5.4 in a sandboxed environment — only the standard library functions that are safe and relevant for embedded use are available.
Programs are generated automatically by the Blockly editor (see BLOCKS.md), but advanced users can write or inspect Lua code directly in the Lua Preview panel.
Tip: Every Blockly block generates a Lua program using the functions documented here. You can inspect the generated code live in the Lua Preview panel while building your program — it is a good way to learn the API from blocks you already know.
- Global Functions
- Constants
- Module:
hub— Hardware I/O and Threading - Module:
lego— LEGO Powered Up Ports - Module:
imu— Orientation and Acceleration - Module:
fastled— Addressable LEDs - Module:
gamepad— Bluetooth Gamepad - Module:
ui— Frontend Display - Module:
alg— Algorithms - Module:
deb— Debug Utilities - Threading Model
- Debugging
- Standard Lua 5.4 Libraries
These functions are available without any module prefix.
Pause execution for ms milliseconds. Yields the FreeRTOS scheduler during the delay.
wait(500) -- pause for 0.5 seconds| Parameter | Type | Description |
|---|---|---|
ms |
integer | Delay in milliseconds |
Send a string to the Logger panel in the IDE and to the serial console.
print("Motor speed set")
print("Value: " .. tostring(speed))| Parameter | Type | Description |
|---|---|---|
str |
string | Message to log |
Return the number of milliseconds since the device last booted.
local start = millis()
wait(100)
local elapsed = millis() - start
print("Elapsed: " .. elapsed .. " ms")Returns: integer
These integer constants are passed as arguments to API functions. The Blockly editor uses them automatically — you only need them when writing Lua directly.
| Constant | Value | Description |
|---|---|---|
PORT1 |
1 |
LEGO port 1 |
PORT2 |
2 |
LEGO port 2 |
PORT3 |
3 |
LEGO port 3 |
PORT4 |
4 |
LEGO port 4 |
Named constants for the ESP32 GPIO pins exposed by the Megahub hardware. Use these instead of raw integers.
These pins support input and output, including FastLED.
| Constant | GPIO number |
|---|---|
GPIO13 |
13 |
GPIO16 |
16 |
GPIO17 |
17 |
GPIO25 |
25 |
GPIO26 |
26 |
GPIO27 |
27 |
GPIO32 |
32 |
GPIO33 |
33 |
These pins are hardware input-only on the ESP32 (no output buffer). They can only be used with hub.digitalRead(), not with hub.digitalWrite(), hub.pinMode(), or fastled.addleds().
| Constant | GPIO number |
|---|---|
GPIO34 |
34 |
GPIO35 |
35 |
GPIO36 |
36 |
GPIO39 |
39 |
The Megahub board uses two SC16IS752 I2C-to-UART bridge chips to interface with the four LEGO ports:
- UART1 (bridge chip 1) — drives ports 1 and 2. Its extra GPIO pins GP4–GP7 are exposed as
UART1_GP4–UART1_GP7. - UART2 (bridge chip 2) — drives ports 3 and 4. Its extra GPIO pins GP4–GP7 are exposed as
UART2_GP4–UART2_GP7.
These GPIO pins belong to the bridge chip, not to the LEGO device plugged in. GP0–GP3 on each chip are used internally for the LEGO port hardware; GP4–GP7 are free for user programs.
These pins support hub.pinMode(), hub.digitalRead(), and hub.digitalWrite(), but not fastled.addleds().
| Constant | Value | Description |
|---|---|---|
UART1_GP4 |
10000 |
GPIO 4 on bridge chip 1 (serves ports 1 & 2) |
UART1_GP5 |
10001 |
GPIO 5 on bridge chip 1 (serves ports 1 & 2) |
UART1_GP6 |
10002 |
GPIO 6 on bridge chip 1 (serves ports 1 & 2) |
UART1_GP7 |
10003 |
GPIO 7 on bridge chip 1 (serves ports 1 & 2) |
UART2_GP4 |
10004 |
GPIO 4 on bridge chip 2 (serves ports 3 & 4) |
UART2_GP5 |
10005 |
GPIO 5 on bridge chip 2 (serves ports 3 & 4) |
UART2_GP6 |
10006 |
GPIO 6 on bridge chip 2 (serves ports 3 & 4) |
UART2_GP7 |
10007 |
GPIO 7 on bridge chip 2 (serves ports 3 & 4) |
| Constant | Value | Description |
|---|---|---|
NEOPIXEL |
1000 |
WS2812B / NeoPixel strip |
| Constant | Value | Description |
|---|---|---|
PINMODE_INPUT |
3000 |
Digital input, floating |
PINMODE_INPUT_PULLUP |
3001 |
Digital input with internal pull-up |
PINMODE_INPUT_PULLDOWN |
3002 |
Digital input with internal pull-down |
PINMODE_OUTPUT |
3003 |
Digital output |
| Constant | Value | Description |
|---|---|---|
GAMEPAD1 |
4000 |
First paired Bluetooth gamepad |
| Constant | Value |
|---|---|
GAMEPAD_BUTTON_1 |
5000 |
GAMEPAD_BUTTON_2 |
5001 |
GAMEPAD_BUTTON_3 |
5002 |
GAMEPAD_BUTTON_4 |
5003 |
GAMEPAD_BUTTON_5 |
5004 |
GAMEPAD_BUTTON_6 |
5005 |
GAMEPAD_BUTTON_7 |
5006 |
GAMEPAD_BUTTON_8 |
5007 |
GAMEPAD_BUTTON_9 |
5008 |
GAMEPAD_BUTTON_10 |
5009 |
GAMEPAD_BUTTON_11 |
5010 |
GAMEPAD_BUTTON_12 |
5011 |
GAMEPAD_BUTTON_13 |
5012 |
GAMEPAD_BUTTON_14 |
5013 |
GAMEPAD_BUTTON_15 |
5014 |
GAMEPAD_BUTTON_16 |
5015 |
| Constant | Value | Description |
|---|---|---|
GAMEPAD_LEFT_X |
6000 |
Left stick horizontal axis |
GAMEPAD_LEFT_Y |
6001 |
Left stick vertical axis |
GAMEPAD_RIGHT_X |
6002 |
Right stick horizontal axis |
GAMEPAD_RIGHT_Y |
6003 |
Right stick vertical axis |
GAMEPAD_DPAD |
6004 |
D-pad state |
| Constant | Value | Unit | Description |
|---|---|---|---|
YAW |
7000 |
° | Rotation around vertical axis |
PITCH |
7001 |
° | Forward/backward tilt |
ROLL |
7002 |
° | Left/right tilt |
ACCELERATION_X |
7003 |
m/s² | Acceleration along X axis |
ACCELERATION_Y |
7004 |
m/s² | Acceleration along Y axis |
ACCELERATION_Z |
7005 |
m/s² | Acceleration along Z axis |
| Constant | Value | Description |
|---|---|---|
FORMAT_SIMPLE |
2000 |
Plain value display |
General device control: GPIO, motor speed, and Lua thread management.
Set the speed of a LEGO motor connected to the given port.
hub.setmotorspeed(PORT1, 80) -- forward at speed 80
hub.setmotorspeed(PORT1, 0) -- stop
hub.setmotorspeed(PORT2, -50) -- reverse at speed 50| Parameter | Type | Description |
|---|---|---|
port |
integer | Port number (1–4, use PORT1–PORT4) |
speed |
integer | Motor speed: -127 (full reverse) to +127 (full forward), 0 = stop |
Configure a GPIO pin as input or output.
hub.pinMode(GPIO26, PINMODE_OUTPUT)
hub.pinMode(GPIO33, PINMODE_INPUT_PULLUP)| Parameter | Type | Description |
|---|---|---|
pin |
integer | GPIO pin constant |
mode |
integer | One of PINMODE_INPUT, PINMODE_INPUT_PULLUP, PINMODE_INPUT_PULLDOWN, PINMODE_OUTPUT |
Accepted pins: output-capable GPIO pins (GPIO13–GPIO33) and UART expansion pins (UART1_GP4–UART2_GP7). Input-only pins (GPIO34, GPIO35, GPIO36, GPIO39) are not supported.
Read the current logic level of a digital input pin.
local state = hub.digitalRead(GPIO33)
if state == 1 then
print("Button pressed")
end| Parameter | Type | Description |
|---|---|---|
pin |
integer | GPIO pin constant |
Returns: integer — 1 for HIGH, 0 for LOW
Accepted pins: all GPIO pins (GPIO13–GPIO39) and UART expansion pins (UART1_GP4–UART2_GP7).
Write a logic level to a digital output pin.
hub.digitalWrite(GPIO26, 1) -- HIGH
hub.digitalWrite(GPIO26, 0) -- LOW| Parameter | Type | Description |
|---|---|---|
pin |
integer | GPIO pin constant |
value |
integer | 1 for HIGH, 0 for LOW |
Accepted pins: output-capable GPIO pins (GPIO13–GPIO33) and UART expansion pins (UART1_GP4–UART2_GP7). Input-only pins (GPIO34, GPIO35, GPIO36, GPIO39) are not supported.
Run the provided function once as an initialization block before the main program loop. Used by the Blockly editor to separate setup code from loop code.
hub.init(function()
hub.setmotorspeed(PORT1, 0)
fastled.addleds(NEOPIXEL, GPIO13, 8)
end)| Parameter | Type | Description |
|---|---|---|
function |
function | Zero-argument function to execute once |
Start a new concurrent Lua thread running on a dedicated FreeRTOS task. Returns a task handle that can be used with hub.stopthread().
local motorThread = hub.startthread("motor", "block_1", 4096, false, function()
hub.setmotorspeed(PORT1, 60)
wait(500)
hub.setmotorspeed(PORT1, 0)
wait(500)
end)| Parameter | Type | Description |
|---|---|---|
name |
string | Human-readable thread name (for diagnostics) |
blockId |
string | Blockly block ID (used for profiling overlay in the IDE) |
stackSize |
integer | FreeRTOS stack size in bytes (minimum ~4096) |
profiling |
boolean | If true, reports min/avg/max execution time to the IDE every 10 seconds |
function |
function | Zero-argument function called in a loop on each task tick |
Returns: task handle (userdata) — pass to hub.stopthread() to stop the thread
Notes:
- The thread function is called repeatedly in a tight loop with a 1 ms
vTaskDelaybetween iterations - If the thread function raises a Lua error, the thread exits and all LEGO device ports are reinitialized
- Each thread has its own Lua coroutine state
Stop a running thread started with hub.startthread().
hub.stopthread(motorThread)| Parameter | Type | Description |
|---|---|---|
handle |
userdata | Task handle returned by hub.startthread() |
Read sensor data and configure device modes on LEGO Powered Up ports.
Select the active measurement mode for the device connected to a port. Mode IDs are device-specific — see the Port Status panel in the IDE for the modes available on your connected device.
lego.selectmode(PORT1, 0) -- select mode 0 (often the default sensor mode)| Parameter | Type | Description |
|---|---|---|
port |
integer | Port number (1–4) |
mode |
integer | Mode index (device-specific, 0-based) |
Read a value from the currently selected mode on a port. A mode may provide multiple datasets (e.g. RGB channels from a colour sensor are three separate datasets).
lego.selectmode(PORT2, 0)
local color = lego.getmodedataset(PORT2, 0)
print("Color index: " .. color)-- Read all three RGB channels (mode 6 on BOOST color/distance sensor)
lego.selectmode(PORT3, 6)
local r = lego.getmodedataset(PORT3, 0)
local g = lego.getmodedataset(PORT3, 1)
local b = lego.getmodedataset(PORT3, 2)| Parameter | Type | Description |
|---|---|---|
port |
integer | Port number (1–4) |
dataset |
integer | Dataset index within the current mode (0-based) |
Returns: number — sensor value for the selected mode/dataset. Returns 0 if no device is connected or the dataset is unavailable.
Mode IDs and dataset layouts are device-specific. The Port Status panel in the IDE lists every mode reported by the connected device, including its name, units, and number of datasets — that is always the authoritative source.
The table below documents confirmed modes for commonly used devices.
| Mode | Name | Units | Datasets | Description |
|---|---|---|---|---|
0 |
COLOR |
IDX | 1 | Detected colour index (0–10; 0 = no colour) |
1 |
PROX |
DIS | 1 | Proximity distance (0–10; 0 = very close) |
6 |
RGB I |
RAW | 3 | Raw RGB intensities — dataset 0=R, 1=G, 2=B |
-- Read proximity on port 2
lego.selectmode(PORT2, 1)
local prox = lego.getmodedataset(PORT2, 0)
-- Read raw RGB on port 3
lego.selectmode(PORT3, 6)
local r = lego.getmodedataset(PORT3, 0)
local g = lego.getmodedataset(PORT3, 1)
local b = lego.getmodedataset(PORT3, 2)Mode data for WeDo 2.0, SPIKE, and Technic devices follows the same pattern. Connect the device, open the Port Status panel, and read the mode list directly from the device. Contributions to this table are welcome.
Read data from the on-board MPU6050 6-axis IMU. Values are updated every 100 ms.
Read an IMU measurement.
local yaw = imu.value(YAW)
local pitch = imu.value(PITCH)
local roll = imu.value(ROLL)
local ax = imu.value(ACCELERATION_X)| Parameter | Type | Description |
|---|---|---|
type |
integer | One of the IMU value constants (see Constants) |
Returns: number — the requested measurement. Returns 0 for unsupported types.
| Type | Unit | Typical range |
|---|---|---|
YAW |
° | 0–360 |
PITCH |
° | -90–+90 |
ROLL |
° | -180–+180 |
ACCELERATION_X/Y/Z |
m/s² | varies |
Control WS2812B (NeoPixel) LED strips. Supported output pins: GPIO13, GPIO16, GPIO17, GPIO25, GPIO26, GPIO27, GPIO32, GPIO33.
Initialize a LED strip. Must be called once before using fastled.set() or fastled.show().
fastled.addleds(NEOPIXEL, GPIO13, 8) -- 8 NeoPixels on GPIO 13| Parameter | Type | Description |
|---|---|---|
type |
integer | Strip type — currently only NEOPIXEL (1000) is supported |
pin |
integer | GPIO output pin — one of the output-capable GPIO constants: GPIO13, GPIO16, GPIO17, GPIO25, GPIO26, GPIO27, GPIO32, GPIO33. UART expansion pins and input-only pins are not supported. |
count |
integer | Number of LEDs in the strip |
Note: addleds automatically calls fastled.clear() after initializing.
Set the colour of a single LED. Changes are not visible until fastled.show() is called.
fastled.set(0, 255, 0, 0) -- first LED red
fastled.set(1, 0, 255, 0) -- second LED green
fastled.set(2, 0, 0, 255) -- third LED blue| Parameter | Type | Description |
|---|---|---|
index |
integer | LED index (0-based) |
r |
integer | Red channel (0–255) |
g |
integer | Green channel (0–255) |
b |
integer | Blue channel (0–255) |
Push all buffered LED colours to the strip. Nothing is displayed until this is called.
fastled.set(0, 255, 128, 0)
fastled.show()Set all LEDs to off (black). Does not call show() — call fastled.show() afterwards to apply.
fastled.clear()
fastled.show()Read the state of a paired Bluetooth Classic HID gamepad. Pair the gamepad via the Bluetooth Devices panel in the IDE before using these functions.
Check whether the gamepad is currently connected.
if gamepad.connected(GAMEPAD1) then
print("Gamepad ready")
end| Parameter | Type | Description |
|---|---|---|
index |
integer | Gamepad identifier — currently only GAMEPAD1 (4000) is supported |
Returns: boolean
Known issue: Due to a firmware bug,
gamepad.connected()may not return a value when the gamepad is connected. The return value is only reliable when the gamepad is not connected (returnsfalse). Usegamepad.buttonsraw()as a workaround to verify connectivity.
Check whether a specific button is currently pressed.
if gamepad.buttonpressed(GAMEPAD1, GAMEPAD_BUTTON_1) then
hub.setmotorspeed(PORT1, 80)
end| Parameter | Type | Description |
|---|---|---|
index |
integer | Gamepad identifier (GAMEPAD1) |
button |
integer | Button constant (GAMEPAD_BUTTON_1 – GAMEPAD_BUTTON_16) |
Returns: boolean — true if pressed, false otherwise
Read an analog axis value.
local x = gamepad.value(GAMEPAD1, GAMEPAD_LEFT_X)
local y = gamepad.value(GAMEPAD1, GAMEPAD_LEFT_Y)| Parameter | Type | Description |
|---|---|---|
index |
integer | Gamepad identifier (GAMEPAD1) |
axis |
integer | Axis constant (see Gamepad axes) |
Returns: number
- Stick axes: -32768 to +32767
- D-pad (
GAMEPAD_DPAD): device-specific integer encoding direction
Known issue: Due to a firmware bug,
GAMEPAD_RIGHT_XandGAMEPAD_RIGHT_Ycurrently return the left stick values instead of the right stick. Use onlyGAMEPAD_LEFT_XandGAMEPAD_LEFT_Yfor reliable readings until this is fixed.
Read the raw button bitmask. Bit 0 = button 1, bit 1 = button 2, etc.
local bits = gamepad.buttonsraw(GAMEPAD1)| Parameter | Type | Description |
|---|---|---|
index |
integer | Gamepad identifier (GAMEPAD1) |
Returns: integer bitmask
Send values to the IDE for real-time display in the Logger panel.
Display a labelled value in the IDE. The value is queued and pushed to the frontend asynchronously.
ui.showvalue("Motor speed", FORMAT_SIMPLE, speed)
ui.showvalue("Connected", FORMAT_SIMPLE, gamepad.connected(GAMEPAD1))
ui.showvalue("Sensor", FORMAT_SIMPLE, lego.getmodedataset(PORT1, 0))| Parameter | Type | Description |
|---|---|---|
label |
string | Label displayed before the value |
format |
integer | Display format — currently only FORMAT_SIMPLE (2000) |
value |
number, string, or boolean | Value to display |
Mathematical algorithms for control applications: PID control and dead reckoning.
The PID controller uses:
- Derivative on measurement (not on error) to avoid setpoint kick
- Anti-windup via back-calculation clamping of the integral term
Create a new PID controller instance and return a unique handle. Store the handle in a variable for use with alg.computePID() and alg.resetPID().
local myPID = alg.initPID()Returns: string — unique handle (e.g., "pid_0", "pid_1", ...)
Compute one step of a PID controller using an explicit handle. The handle must be obtained from alg.initPID().
-- Follow a target distance of 30 cm using a distance sensor
local myPID = alg.initPID()
-- In control loop:
local setpoint = 30
local pv = lego.getmodedataset(PORT1, 0)
local output = alg.computePID(myPID, setpoint, pv, 2.0, 0.1, 0.05, -127, 127)
hub.setmotorspeed(PORT2, math.floor(output))| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initPID() |
setpoint |
number | Target (desired) value |
pv |
number | Process variable (current measured value) |
kp |
number | Proportional gain |
ki |
number | Integral gain |
kd |
number | Derivative gain |
outMin |
number | Lower clamp on the output |
outMax |
number | Upper clamp on the output |
Returns: number — control output, clamped to [outMin, outMax]. Returns 0 on the first call (dt is zero on the first iteration) or if the handle is not found.
Reset the state (integral, previous error, and timestamp) of a specific PID controller.
local myPID = alg.initPID()
-- ... use the controller ...
alg.resetPID(myPID) -- Reset when switching setpoints| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initPID() |
Clear the state of all PID controller instances.
alg.clearAllPID()Dead reckoning estimates a robot's position and heading by integrating wheel encoder and IMU sensor readings over time. The implementation:
- Fuses differential drive kinematics with IMU yaw measurements
- Uses the ROS REP 103/105 coordinate system (+X forward, +Y left, heading counterclockwise from +X)
- Requires motors in POS mode (use
lego.selectmode(port, 2)for standard LEGO motors)
See DEADRECKONING.md for algorithm details.
Create a new dead reckoning instance and return a unique handle. Store the handle in a variable for use with other DR functions.
local myRobot = alg.initDR()Returns: string — unique handle (e.g., "dr_0", "dr_1", ...)
Update the dead reckoning state with new encoder and IMU readings. Call this regularly (e.g., every 50–100 ms) in your control loop.
local myRobot = alg.initDR()
-- In control loop:
local leftTicks = lego.getmodedataset(PORT1, 0)
local rightTicks = lego.getmodedataset(PORT2, 0)
local yaw = imu.value(YAW)
alg.updateDR(myRobot, leftTicks, rightTicks, yaw, 0.12, 0.0005, 0.8)| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initDR() |
leftTicks |
number | Current left encoder reading (absolute position) |
rightTicks |
number | Current right encoder reading (absolute position) |
yawDeg |
number | Current IMU yaw reading in degrees (0–360) |
wheelbase |
number | Distance between left and right wheels in meters |
mPerTick |
number | Meters of travel per encoder tick |
imuWeight |
number | IMU fusion weight (0.0 = pure odometry, 1.0 = pure IMU, 0.8 recommended) |
Note: The first call to updateDR() initializes the state and does not update the pose (it just records the initial sensor readings). Position updates begin on the second call.
Get a component of the current estimated pose.
local x = alg.drGet(myRobot, "x") -- meters, +X forward
local y = alg.drGet(myRobot, "y") -- meters, +Y left
local heading = alg.drGet(myRobot, "heading") -- degrees, CCW from +X| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initDR() |
field |
string | Field name: "x", "y", or "heading" |
Returns: number
"x"and"y": position in meters (ROS REP 103 convention)"heading": orientation in degrees (counterclockwise from +X axis)
Returns 0 if the handle is not found or the field name is invalid.
Reset the dead reckoning state to the origin (x=0, y=0, heading=0) and mark it uninitialized. The next updateDR() call will re-bootstrap from current sensor readings.
alg.drReset(myRobot)| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initDR() |
Inject a known pose into the dead reckoning state. Use this to:
- Set an initial pose before starting the control loop
- Correct drift using external localization (e.g., detected landmarks)
-- Set initial position at (1.5, 0.5) facing 45 degrees
alg.drSetPose(myRobot, 1.5, 0.5, 45)| Parameter | Type | Description |
|---|---|---|
handle |
string | Handle from alg.initDR() |
x |
number | X position in meters |
y |
number | Y position in meters |
headingDeg |
number | Heading in degrees (counterclockwise from +X) |
Note: This updates the pose but does not reset the encoder/IMU baselines. The next updateDR() call will compute deltas from the current sensor readings.
Clear the state of all dead reckoning instances.
alg.clearAllDR()Diagnostic helpers for development.
Return the number of bytes of free heap memory currently available on the ESP32.
print("Free heap: " .. deb.freeHeap() .. " bytes")Returns: integer
Megahub programs use cooperative multitasking via FreeRTOS tasks.
- The main Lua program runs on a single thread and executes to completion (or until
wait()yields). - Additional threads created with
hub.startthread()each run on their own FreeRTOS task with a dedicated Lua coroutine state. - All threads share the same device state (ports, LED strip, etc.), so call order is not guaranteed if multiple threads control the same device simultaneously.
- When the program is stopped from the IDE, all running threads are cancelled and all LEGO device ports are reinitialized.
- If any thread exits due to a Lua error, all ports are also reinitialized automatically.
Typical program structure:
-- Initialization: runs once
hub.init(function()
hub.setmotorspeed(PORT1, 0)
fastled.addleds(NEOPIXEL, GPIO13, 8)
fastled.clear()
fastled.show()
end)
-- Thread 1: motor control loop
local motorThread = hub.startthread("motor", "blk_motor", 4096, false, function()
local speed = gamepad.value(GAMEPAD1, GAMEPAD_LEFT_Y) / 256
hub.setmotorspeed(PORT1, math.floor(speed))
wait(20)
end)
-- Thread 2: LED feedback loop
local ledThread = hub.startthread("leds", "blk_leds", 4096, false, function()
local yaw = imu.value(YAW)
local hue = math.floor(yaw / 360 * 255)
for i = 0, 7 do
fastled.set(i, hue, 0, 255 - hue)
end
fastled.show()
wait(50)
end)All errors from running Lua code are sent to the Logger panel in the IDE and to the serial console (115200 baud). The format is:
[string]:LINE: ERROR MESSAGE
Example:
[string]:5: attempt to perform arithmetic on a nil value (global 'speed')
The line number refers to the line in your Lua program (visible in the Lua Preview panel). The error appears in the Logger immediately when the thread or program crashes.
Any of the following causes all four LEGO ports to reinitialize (motors stop, sensors reset):
| Event | Ports reinit? |
|---|---|
| Click Execute | Yes — always |
| Click Stop | Yes — always |
| Runtime error in a thread | Yes |
| Runtime error in main program body | Yes |
Error inside hub.init() |
No — the error is logged but execution continues |
hub.init()errors are silently swallowed after logging. If your initialization seems to have no effect, check the Logger for a[WARN] Error processing Lua functionmessage.
Insert print() calls to trace execution flow and variable values:
print("Starting motor loop")
local speed = gamepad.value(GAMEPAD1, GAMEPAD_LEFT_Y)
print("Raw stick Y: " .. tostring(speed))
hub.setmotorspeed(PORT1, math.floor(speed / 256))Every print() call appears immediately in the Logger panel.
If a program crashes after running for a while, a memory leak may be the cause. Log the free heap regularly to watch for a downward trend:
local ledThread = hub.startthread("monitor", "blk_mon", 2048, false, function()
print("Free heap: " .. deb.freeHeap() .. " bytes")
wait(5000)
end)A healthy program holds a roughly constant heap. If the number drops steadily, the program is allocating memory it never frees (for example, building up large strings or tables inside a tight loop).
Pass profiling = true to hub.startthread() to receive timing statistics every 10 seconds in the IDE:
hub.startthread("motor", "blk_motor", 4096, true, function()
-- ...
wait(20)
end)The IDE displays a thread_statistics event with min, avg, and max iteration times in microseconds. Use this to confirm your thread is keeping up with its intended update rate — for example, a motor control loop running at 20 ms intervals should show an avg well below 20 000 µs.
| Symptom | Likely cause |
|---|---|
| LEDs don't change colour | fastled.set() was called but fastled.show() was not |
Sensor always returns 0 |
lego.selectmode() was not called before lego.getmodedataset() |
| Program does nothing, no error | Error inside hub.init() — check Logger for [WARN] |
| Device crashes / reboots | Thread stack too small; try increasing stackSize (minimum ~4096 bytes) |
| Motor doesn't stop after program ends | Not expected — motors always stop on Execute, Stop, or crash |
hub.init() changes have no effect |
hub.init() must be called before hub.startthread() — it runs synchronously |
All standard Lua 5.4 libraries are loaded automatically at program start. The table below lists each library, its global name, and any caveats relevant to the embedded ESP32 environment. For the full API reference, see the Lua 5.4 manual.
| Library | Global name | Notes |
|---|---|---|
| Base | (global scope) | assert, error, ipairs, pairs, pcall, print, rawget, rawset, select, setmetatable, tostring, tonumber, type, xpcall, next, unpack, and others. Fully available. Note: print() on Megahub is overridden to send output to the IDE Logger panel instead of stdout. |
| String | string |
Full Lua 5.4 string library. Pattern matching, string.format, string.sub, string.find, string.gmatch, string.gsub, etc. Fully available. |
| Math | math |
Full Lua 5.4 math library. math.floor, math.ceil, math.abs, math.sin, math.cos, math.sqrt, math.random, math.huge, math.pi, etc. Fully available. |
| Table | table |
table.insert, table.remove, table.sort, table.concat, table.move, table.unpack. Fully available. |
| Coroutine | coroutine |
coroutine.create, coroutine.resume, coroutine.yield, coroutine.status, coroutine.wrap. Fully available. Used internally by hub.startthread(). |
| UTF-8 | utf8 |
utf8.char, utf8.codepoint, utf8.codes, utf8.len, utf8.offset. Fully available. |
| Package | package |
require for loading Lua modules. Useful only if you have Lua module files on the device filesystem. package.loadlib (C dynamic loading) is not available on ESP32. |
| IO | io |
File I/O functions (io.open, io.lines, etc.). Limited on ESP32: the device filesystem is not accessible to Lua scripts; file operations will fail. Standard streams io.stdin, io.stdout, and io.stderr map to the UART serial console. |
| OS | os |
Partially available. os.clock(), os.time(), and os.difftime() work normally. os.execute(), os.exit(), os.getenv(), os.remove(), os.rename(), and os.tmpname() are not meaningful on the ESP32 and should not be used. |
| Debug | debug |
debug.traceback(), debug.getinfo(), debug.sethook(), and related functions. Useful for advanced debugging. debug.traceback() is particularly helpful inside pcall error handlers to get a full stack trace. |