diff --git a/.gitignore b/.gitignore index 2315c46..a4f2a15 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,2 @@ tools/venv/* - +.idea \ No newline at end of file diff --git a/examples/.keep b/examples/.keep deleted file mode 100644 index e69de29..0000000 diff --git a/examples/main.c b/examples/main.c new file mode 100644 index 0000000..2b490cf --- /dev/null +++ b/examples/main.c @@ -0,0 +1,35 @@ +#include "edstream.h" +#include "edstream_hal.h" + +#include + +#define LOG_LOCAL_LEVEL ESP_LOG_ERROR +#include "esp_log.h" + +void receiver(void *pvParameters) +{ + struct eds_hal_config eds_hal_conf = eds_hal_default(); + eds_hal_init(&eds_hal_conf); + + ssd1306_128x64_i2c_init(); + + ssd1306_clearScreen(); + + uint8_t cmd[512]; + int read; + + while(true) { + vTaskDelay(1); + read = eds_hal_recv(cmd, 512); + if (read <= 0) continue; + ESP_LOGD("RX", "Read bytes: %d", read); + eds_decode_message(cmd, read); + } + + vTaskDelete(NULL); +} + +void app_main() +{ + xTaskCreate(receiver, "receiver", 8192, NULL, 0, NULL); // Yep, this is a huge amount of memory +} \ No newline at end of file diff --git a/include/edstream.h b/include/edstream.h index 479d588..23d5bfb 100644 --- a/include/edstream.h +++ b/include/edstream.h @@ -9,32 +9,37 @@ */ // Receiver should save this frame (as part of animation) -#define PROTOCOL_SAVE_FRAME (0x01 << 0) +#define PROTOCOL_SAVE_FRAME (0x01 << 0) // Sent frame is zipped -#define PROTOCOL_ZIPPED_FRAME (0x01 << 1) +#define PROTOCOL_ZIPPED_FRAME (0x01 << 1) // This msg. sets the refresh rate of the animation. Expected payload // is 1 byte with refresh rate in milliseconds (as uint8_t) -#define PROTOCOL_SET_FREQ (0x01 << 2) +#define PROTOCOL_SET_FREQ (0x01 << 2) // XOR function. If set starts/stops the animation. No payload is // expected #define PROTOCOL_TOGGLE_ANIMATION (0x01 << 3) // Clear animation buffer -#define PROTOCOL_CLEAR_BUF (0x01 << 4) +#define PROTOCOL_CLEAR_BUF (0x01 << 4) -#define PROTOCOL_QUERY (0x01 << 7) +#define PROTOCOL_QUERY (0x01 << 7) -#define QUERY_IS_ANIMATION_RUNNING 0x01 -#define QUERY_SUPPORTED_FX 0x02 -#define QUERY_BUFFER_SIZE 0x03 +#define QUERY_IS_ANIMATION_RUNNING (0x01) +#define QUERY_SUPPORTED_FX (0x02) +#define QUERY_BUFFER_SIZE (0x03) + +#define RESPONSE_ACK (0xff) + +#define FRAME_SIZE (1024) +#define MAX_FRAME_NUMBER (14) /* * Controller functions */ -int eds_send_frame(uint8_t *frame, bool save, bool zip); +int eds_send_frame(const uint8_t *frame, bool save, bool zip); int eds_start_animation(); int eds_stop_animation(); @@ -43,13 +48,16 @@ bool eds_query_animation_status(); typedef void(*eds_zip_function_t)(uint8_t *src, uint8_t *dst, int *pl_size); void eds_zip_function_set(eds_zip_function_t f); void eds_zip_deflate(uint8_t *src, uint8_t *dst, int *pl_size); -eds_zip_function_t eds_zip_function = eds_zip_deflate; /* * Device functions */ // Callback function to decode messages -int eds_decode_message(uint8_t *payload, int i); +int eds_decode_message(const uint8_t *payload, int i); + +int eds_send_ack(void); +void eds_toggle_animation(void); +void eds_clear_framebuffer(void); #endif //__EDSTREAM_H \ No newline at end of file diff --git a/platformio.ini b/platformio.ini index 8d4dad5..68de490 100644 --- a/platformio.ini +++ b/platformio.ini @@ -13,4 +13,4 @@ platform = espressif32 board = esp32doit-devkit-v1 framework = espidf monitor_speed = 115200 -monitor_filter = direct +monitor_filters = direct diff --git a/src/edstream.c b/src/edstream.c index 12d3c4c..ba430db 100644 --- a/src/edstream.c +++ b/src/edstream.c @@ -1,9 +1,20 @@ -#include - #include "edstream.h" #include "edstream_hal.h" +#define LOG_LOCAL_LEVEL ESP_LOG_NONE +#include "esp_log.h" + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include + static bool is_animation_running = false; +static int refresh_rate = 33; // ms +static eds_zip_function_t eds_zip_function = eds_zip_deflate; + +static uint8_t framebuffer[FRAME_SIZE * MAX_FRAME_NUMBER]; +static int framebuffer_size = 0; /* * @brief Sends a frame to display device (that controls the display) @@ -14,7 +25,8 @@ static bool is_animation_running = false; * * You can provide a Deflate function with eds_zip_function_set() */ -int eds_send_frame(uint8_t *frame, bool save, bool zip) { +int eds_send_frame(const uint8_t *frame, bool save, bool zip) +{ uint8_t message[1025]; message[0] = save ? PROTOCOL_SAVE_FRAME : 0 | @@ -30,8 +42,9 @@ int eds_send_frame(uint8_t *frame, bool save, bool zip) { return 0; } -bool eds_query_animation_status() { - uint16_t message = PROTOCOL_QUERY << 16 + QUERY_IS_ANIMATION_RUNNING; +bool eds_query_animation_status() +{ + uint16_t message = (PROTOCOL_QUERY << 16) + QUERY_IS_ANIMATION_RUNNING; eds_hal_send(&message, 2); eds_hal_recv(&is_animation_running, 1); @@ -39,40 +52,85 @@ bool eds_query_animation_status() { return is_animation_running; } -int eds_start_animation() { +void eds_show_animation_task(void* pvParameters) +{ + int local_frame_counter = 0; + ESP_LOGD("SHOW", "Entering while loop"); + while (is_animation_running) { + eds_hal_display_show(framebuffer + local_frame_counter*FRAME_SIZE); + local_frame_counter++; + local_frame_counter %= framebuffer_size; + vTaskDelay(refresh_rate/portTICK_PERIOD_MS); + } + ESP_LOGD("SHOW", "Exiting while loop of show_animation_task"); + vTaskDelete(NULL); +} +int eds_start_animation() +{ if(!is_animation_running) { - eds_hal_send(PROTOCOL_TOGGLE_ANIMATION, 1); + ESP_LOGD("START", "Start automation"); + // eds_hal_send(PROTOCOL_TOGGLE_ANIMATION, 1); is_animation_running = true; + xTaskCreate(eds_show_animation_task, "show_animation_task", 8192, NULL, 5, NULL); // TODO: Guru meditation error } return 0; } -int eds_stop_animation() { - +int eds_stop_animation() +{ if(is_animation_running) { - eds_hal_send(PROTOCOL_TOGGLE_ANIMATION, 1); - is_animation_running = false; + // eds_hal_send(PROTOCOL_TOGGLE_ANIMATION, 1); + is_animation_running = false; // show_animation_task exits from loop and destroys himself } return 0; } +int eds_send_ack(void) +{ + ESP_LOGD("ACK", "Sending ACK to controller"); + return eds_hal_send_byte(RESPONSE_ACK); +} + +void eds_toggle_animation(void) +{ + ESP_LOGD("TOGGLE", "toggle animation"); + if (is_animation_running) + eds_stop_animation(); + else + eds_start_animation(); +} + +void eds_clear_framebuffer(void) +{ + framebuffer_size = 0; +} + + enum eds_fsm_states { FSM_WAIT_MESSAGE, FSM_NEW_MESSAGE, FSM_QUERY, FSM_CONTROL, FSM_RECV_FRAME, + FSM_CLEAR_BUF, + FSM_TOGGLE_ANIMATION, + FSM_SAVE_FRAME, FSM_MAX_STATES }; + static int eds_fsm_state = FSM_WAIT_MESSAGE; -static uint8_t current_frame[1024]; /* * @return 0 on no error */ -int eds_decode_message(uint8_t *payload, int n) { +int eds_decode_message(const uint8_t *payload, int n) +{ int i = 0; //consumed bytes static int received_frame_bytes = 0; + static int frame_counter = 0; + bool is_zipped = false; + + ESP_LOGI("FSM", "Called FSM with %d bytes of payload", n); while(i < n) { switch(eds_fsm_state) { @@ -81,16 +139,21 @@ int eds_decode_message(uint8_t *payload, int n) { break; case FSM_NEW_MESSAGE: - if(payload[i] && PROTOCOL_QUERY) { + if (payload[i] & PROTOCOL_QUERY) { eds_fsm_state = FSM_QUERY; - i++; - } else if (payload[i] >= PROTOCOL_SET_FREQ) { + } else if (payload[i] & PROTOCOL_CLEAR_BUF) { + eds_fsm_state = FSM_CLEAR_BUF; + } else if (payload[i] & PROTOCOL_TOGGLE_ANIMATION) { + eds_fsm_state = FSM_TOGGLE_ANIMATION; + } else if (payload[i] & PROTOCOL_SET_FREQ) { eds_fsm_state = FSM_CONTROL; + } else if (payload[i] & PROTOCOL_SAVE_FRAME) { + eds_fsm_state = FSM_SAVE_FRAME; } else { - eds_fsm_state = FSM_RECV_FRAME; - received_frame_bytes = 0; - i++; + eds_fsm_state = FSM_WAIT_MESSAGE; } + ESP_LOGD("FSM", "Payload is i-1]: %x [i]: %x and next state will be %d\n", payload[i-1], payload[i], eds_fsm_state); + eds_send_ack(); break; case FSM_QUERY: @@ -101,20 +164,48 @@ int eds_decode_message(uint8_t *payload, int n) { eds_hal_send_byte(10); if(payload[i] == QUERY_SUPPORTED_FX) - eds_hal_send_byte(0x00); // still dummy + eds_hal_send_byte(0x00); i++; eds_fsm_state = FSM_WAIT_MESSAGE; break; case FSM_RECV_FRAME: - current_frame[received_frame_bytes++] = payload[i++]; + framebuffer[(received_frame_bytes++) + (FRAME_SIZE*frame_counter)] = payload[i++]; + ESP_LOGD("FSM", "Bytes counter: %d", received_frame_bytes); if(received_frame_bytes == 1024) { - eds_hal_display_show(current_frame); + ESP_LOGI("FSM", "Saved..."); eds_fsm_state = FSM_WAIT_MESSAGE; + framebuffer_size++; + frame_counter++; + eds_send_ack(); } break; + case FSM_CLEAR_BUF: + ESP_LOGD("FSM", "Clear buffer"); + frame_counter = 0; + eds_clear_framebuffer(); + eds_fsm_state = FSM_WAIT_MESSAGE; + i++; + break; + + case FSM_TOGGLE_ANIMATION: + ESP_LOGD("FSM", "Toggle animation"); + eds_toggle_animation(); + eds_fsm_state = FSM_WAIT_MESSAGE; + i++; + break; + + case FSM_SAVE_FRAME: + ESP_LOGD("FSM", "Save frame"); + is_zipped = payload[i] & PROTOCOL_ZIPPED_FRAME; + i++; + received_frame_bytes = 0; + eds_fsm_state = FSM_RECV_FRAME; + ESP_LOGD("FSM", "Exiting from save frame state"); + break; + default: eds_fsm_state = FSM_WAIT_MESSAGE; } diff --git a/src/edstream_hal.c b/src/edstream_hal.c index e69de29..cc9eef6 100644 --- a/src/edstream_hal.c +++ b/src/edstream_hal.c @@ -0,0 +1,55 @@ +/* + * EDStream HAL implementation + * (c) 2021 - Project EDStream + * + * ESP32 I2C_0 and UART_0 + */ + +#include "edstream_hal.h" + +#define LOG_LOCAL_LEVEL ESP_LOG_NONE +#include "esp_log.h" +#include "ssd1306.h" +#include "driver/uart.h" + +static struct eds_hal_config configuration; + +static uint8_t uart_num_mem; +static QueueHandle_t queue_handle; + +void eds_hal_init(const struct eds_hal_config *config) { + + configuration = *config; + + // I2C + ssd1306_platform_i2cConfig_t cfg = { + .sda = config->i2c_pins.sda, + .scl = config->i2c_pins.scl + }; + ssd1306_platform_i2cInit(config->i2c_num, 0, &cfg); + + // UART + ESP_ERROR_CHECK(uart_param_config(config->uart_num, &(config->uart_conf))); + ESP_ERROR_CHECK(uart_set_pin(config->uart_num, config->uart_pins.tx, config->uart_pins.rx, config->uart_pins.rts, config->uart_pins.cts)); + ESP_ERROR_CHECK(uart_driver_install(config->uart_num, config->uart_buf_size, config->uart_buf_size, 10, &queue_handle, 0)); + uart_num_mem = config->uart_num; +} + +int eds_hal_send_byte(uint8_t x) { + return eds_hal_send(&x, 1); +} + +int eds_hal_send(const uint8_t *src, int n) { + size_t res = uart_write_bytes(uart_num_mem, (const char*) src, n); + uart_wait_tx_done(uart_num_mem, 100); // timeout of 100 ticks + return res; +} + +int eds_hal_recv(uint8_t *dst, int n) { + return uart_read_bytes(UART_NUM_0, dst, n, 100 / portTICK_RATE_MS); +} + +int eds_hal_display_show(const uint8_t *frame) { + ssd1306_drawBuffer(0, 0, OLED_W, OLED_H, frame); + return 0; +} \ No newline at end of file diff --git a/src/edstream_hal.h b/src/edstream_hal.h index 07b2108..e0b3c2b 100644 --- a/src/edstream_hal.h +++ b/src/edstream_hal.h @@ -1,7 +1,57 @@ +#ifndef __EDSTREAM_HAL +#define __EDSTREAM_HAL + #include "stdint.h" #include "stdbool.h" +#include "driver/uart.h" + +#define OLED_W (128) +#define OLED_H (64) +#define UART_NUM (UART_NUM_0) // Connected to CP2102 +#define UART_BUF_SIZE (2048) + +static struct _i2c_pins { + uint8_t sda; + uint8_t scl; +}; + +static struct _uart_pins { + int tx; // -1 is valid + int rx; + int rts; + int cts; +}; + +struct eds_hal_config { + uint8_t i2c_num; + uint8_t uart_num; + struct _i2c_pins i2c_pins; + struct _uart_pins uart_pins; + uart_config_t uart_conf; + uint16_t uart_buf_size; +}; +#define eds_hal_default() ((struct eds_hal_config){ .i2c_num=0, \ + .i2c_pins = {.sda=21, .scl=22}, \ + .uart_conf = {.baud_rate=115200, .data_bits=UART_DATA_8_BITS, .parity=UART_PARITY_DISABLE, \ + .stop_bits=UART_STOP_BITS_1, .flow_ctrl=UART_HW_FLOWCTRL_DISABLE, .rx_flow_ctrl_thresh=122}, \ + .uart_num = UART_NUM, \ + .uart_pins = {.tx=UART_PIN_NO_CHANGE, .rx=UART_PIN_NO_CHANGE, .rts=18, .cts=19}, \ + .uart_buf_size = UART_BUF_SIZE \ + }) + +void eds_hal_init(const struct eds_hal_config *config); -int eds_hal_send(uint8_t *src, int i); int eds_hal_send_byte(uint8_t x); -int eds_hal_recv(uint8_t *dst, int i); -int eds_hal_display_show(uint8_t *frame); \ No newline at end of file + +/* + * @return Number of sent bytes to UART + */ +int eds_hal_send(const uint8_t *src, int n); + +/* + * @return Number of read bytes from UART + */ +int eds_hal_recv(uint8_t *dst, int n); +int eds_hal_display_show(const uint8_t *frame); + +#endif \ No newline at end of file diff --git a/tools/README.md b/tools/README.md index 2bee73b..3527f0a 100644 --- a/tools/README.md +++ b/tools/README.md @@ -27,7 +27,9 @@ python bitmap_over_uart.py -h ### Image Send an image to the embedded device ``` -cat image.png | python to_bitmap.py | python bitmap_over_uart.py -s +cat image.png | python3 to_bitmap.py | python3 rotate_pixel.py | python3 bitmap_over_uart.py ``` +evnetually set your device serial port with -p option in `bitmap_over_uart.py` script + ### Video sream diff --git a/tools/bitmap_over_uart.py b/tools/bitmap_over_uart.py index d27ed3c..b075d28 100644 --- a/tools/bitmap_over_uart.py +++ b/tools/bitmap_over_uart.py @@ -10,6 +10,8 @@ from io import BytesIO from PIL import Image from enum import IntEnum, auto +from time import sleep +import logging SERIAL_PORT_NAME: str = "/dev/ttyUSB0" # Default value @@ -70,17 +72,21 @@ def __check_ack(self) -> bool: Check if the embedded device acknowledged start or stop byte ACK byte: 0xff """ - return (self.serial_port.read() == b'\xff') + + has_ackd = (self.serial_port.read() == b'\xff') + if not has_ackd: + logging.warning("Device hasn't acknowledged") + return has_ackd def send_bitmap(self, buf: bytes) -> None: """ Send a series of bytes to the embedded device. Store these bytes and save them into the frame buffer :param bytes buf: bytes of which the bitmap image is made up of """ - self.__send_start_byte(zipped = True, save = True, size_128x64 = True) - assert self.__check_ack() + self.__send_start_byte(zipped = False, save = True, size_128x64 = True) + self.__check_ack() self.serial_port.write(buf) - assert self.__check_ack() + self.__check_ack() def set_refresh_rate(self, rr: int) -> None: """ @@ -88,54 +94,58 @@ def set_refresh_rate(self, rr: int) -> None: :param int rr: Refresh Rate value in milliseconds (later divided by portTICK_MS on the ESP32 MCU) """ self.__send_start_byte(set_rr = True) - assert self.__check_ack() - self.serial_port.write(bytes([rr])) - assert self.__check_ack() + self.__check_ack() + self.serial_port.write(byte([rr])) + self.__check_ack() def start(self) -> None: """ Start animation """ self.__send_start_byte(start = True) - assert self.__check_ack() + self.__check_ack() def clear(self) -> None: """ Clear embedded device's frame buffer """ self.__send_start_byte(clear = True) - assert self.__check_ack() - - -def main(serial_port_name: str, show: bool, start_animation: bool, refresh_rate: int, clear: bool) -> None: - if refresh_rate is None and not clear and not start_animation: # These three flags inhibit default behavior. No piped bitmap needed - stdin_img_bytes: BytesIO = BytesIO(sys.stdin.buffer.read()) - if show: # Show preview - img: Image = Image.open(stdin_img_bytes) - scaling_factor = 5 - w: int = img.size[0] * scaling_factor - h: int = img.size[1] * scaling_factor - img.resize((w, h), Image.ANTIALIAS).show() - with serial.Serial(port=serial_port_name, baudrate=115200, bytesize=8, parity='N', stopbits=1, timeout=3) as serial_port: - handler: ProtocolHandler = ProtocolHandler(serial_port) + self.__check_ack() + + +def main(port: str, show: bool, start_animation: bool, refresh_rate: int, clear: bool, use_stdin: bool): + with serial.Serial(port, baudrate=115200, bytesize=8) as uart: + handler = ProtocolHandler(uart) if clear: handler.clear() elif start_animation: handler.start() - elif refresh_rate != None: + elif refresh_rate: handler.set_refresh_rate(refresh_rate) - else: # Default behavior -> send bitmap - handler.send_bitmap(stdin_img_bytes.getvalue()) + else: + if use_stdin: + stdin_img_bytes = BytesIO(sys.stdin.buffer.read()) + img = Image.open(stdin_img_bytes if use_stdin else "lib/edstream/tools/image.bmp") + + if show: # Show preview + scaling_factor = 5 + w: int = img.size[0] * scaling_factor + h: int = img.size[1] * scaling_factor + img.resize((w, h), Image.ANTIALIAS).show() + + handler.send_bitmap(img.tobytes()) + if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument('-p', '--port', help='Serial port name', type=str, default=SERIAL_PORT_NAME) parser.add_argument('-s', '--show', help='Show piped image (on the PC) before sending', default=False, action='store_true') parser.add_argument('--start-animation', help='Start animation on the target device. Inhibit default behavior (send bitmap). No piped image', default=False, action='store_true') + parser.add_argument('--nostdin', help="Open image.bmp instead of stdin", default=True, action='store_false') parser.add_argument('--refresh-rate', help='Set animation refresh rate. Inhibit default behavior (send bitmap). No piped image', type=int, default=None) # rr = None -> skip set_rr flag (false) parser.add_argument('--clear', help='Clear frame buffer stored on the embedded device. Inhibit default behavior (send bitmap). No piped image', default=False, action='store_true') args = parser.parse_args() - main(args.port, args.show, args.start_animation, args.refresh_rate, args.clear) + main(args.port, args.show, args.start_animation, args.refresh_rate, args.clear, args.nostdin) diff --git a/tools/daemon.py b/tools/daemon.py new file mode 100644 index 0000000..2dc5b78 --- /dev/null +++ b/tools/daemon.py @@ -0,0 +1,76 @@ +""" +daemon.py + +MQTT bridge daemon for remote communication with edstream controller. +""" + +__authors__ = "5H wild nerds" + +import argparse +import logging +import paho.mqtt.client as mqtt +import serial +from queue import Queue +import threading +from bitmap_over_uart import ProtocolHandler +from io import BytesIO +from PIL import Image + +class EdstreamMQTT(mqtt.Client): + def __init__(self, frame_queue: Queue, *args, **kwargs): + super().__init__(*args, **kwargs) + self.frame_queue = frame_queue + + def on_connect(self, mqttc, obj, flags, rc): + logging.info(f"Connected to broker with return code {rc}") + self.subscribe("edstream") + + def on_disconnect(self, mqttc, userdata, rc): + if rc != 0: + logging.warning(f"Unexpected disconnection from server. Result code {rc}") + else: + logging.info("Disconnected from broker") + + def on_message(self, mqttc, userdata, message: mqtt.MQTTMessage): + logging.debug(f"Received message from topic {message.topic}") + self.frame_queue.put(message.payload) + + +def main(port, broker_addr): + with serial.Serial(port, baudrate=115200) as s: + frame_queue = Queue() + client = EdstreamMQTT(frame_queue, protocol=mqtt.MQTTv311) + client.connect(broker_addr) + phandler = ProtocolHandler(s) + + t = threading.Thread(target=client.loop_forever) + t.start() + + s.flushInput() + + try: + while True: + frame = frame_queue.get() + + stdin_img_bytes = BytesIO(frame) + img = Image.open(stdin_img_bytes) + + phandler.send_bitmap(img.tobytes()) + + phandler.start() + + except KeyboardInterrupt: + pass + + client.disconnect() + +if __name__ == '__main__': + logging.basicConfig(level=logging.DEBUG) + + parser = argparse.ArgumentParser() + parser.add_argument('-p', '--port', help='Serial port name', type=str, default="/dev/cu.SLAB_USBtoUART") + parser.add_argument('-b', '--broker', help='Broker address', type=str, default="mqtt.ssh.edu.it") + + args = parser.parse_args() + + main(args.port, args.broker) \ No newline at end of file diff --git a/tools/debug_uart.py b/tools/debug_uart.py new file mode 100644 index 0000000..4ed8c32 --- /dev/null +++ b/tools/debug_uart.py @@ -0,0 +1,42 @@ +""" +Tool for UART debugging. Waits for a string on stdin representing the hex +dump of a bytes array. +The tool only writes on the serial port stream, a monitor should read the debug +response from the display controller (e.g. ESP32). +""" + +__authors__ = "5H wild nerds" + +import serial +import argparse +import threading +import logging + +def send_raw_byte(port: serial.Serial, hex_repr: str): + x = bytes.fromhex(hex_repr) + port.write(x) + +def speed_test(port: serial.Serial): + port.write(bytes([0])) + for x in range(256): + port.write(x.to_bytes(1, 'little')) + +def main(port: str, speed: int, speedtest): + with serial.Serial(port, speed) as s: + if speedtest: + speed_test(s) + + while True: + payload = eval(input(">> ")) # 'ff'*256 (string*number of times) is allowed + print(f">> {payload}") + send_raw_byte(s, payload) + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument('-p', '--port', help='Serial port name', default="/dev/cu.SLAB_USBtoUART") + parser.add_argument('-b', '--baudrate', help='Serial port baudrate', type=int, default=115200) + parser.add_argument('-s', '--speedtest', help='Performs a speed test', default=False, action='store_true') + parser.add_argument('-d', '--display', help='Print incoming bytes using a separate thread', default=False, action='store_true') + + args = parser.parse_args() + main(args.port, args.baudrate, args.speedtest) \ No newline at end of file diff --git a/tools/image.png b/tools/image.png index 3c9672e..771e03d 100644 Binary files a/tools/image.png and b/tools/image.png differ diff --git a/tools/rotate_pixel.py b/tools/rotate_pixel.py new file mode 100644 index 0000000..3cc3dc7 --- /dev/null +++ b/tools/rotate_pixel.py @@ -0,0 +1,51 @@ +""" +rotate_pixel.py script + +Converts GLCD or standard horizontal bitmap images to SSD1306 format. +Each byte represents a vertical pixel. Least significant bit is the first row, +therefore a simple rotation of 90 degrees clockwise is needed which is a trivial +operation to perform using Pillow. + +You can invoke this script in your shell pipeline, or use it as a standalone function. +""" + +from PIL import Image +import argparse +import sys +from io import BytesIO + +def GLCD_to_SSD1306(image: Image) -> Image: + output = bytearray() + + for bn in range(8): #block number + block: Image = image.crop((0, bn*8, 128, bn*8+8)) + rblock: Image = block.rotate(-90, expand=True) + output += rblock.tobytes() + + reassembled: Image = Image.frombytes('1', (64, 128), bytes(output)) + return reassembled + + +def main(use_stdin: bool, image: str): + if use_stdin: + stdin_img_bytes = BytesIO(sys.stdin.buffer.read()) + img = Image.open(stdin_img_bytes) + else: + img = Image.open(image) + + reassembled: Image = GLCD_to_SSD1306(img) + + img_byte_array = BytesIO() + reassembled.save(img_byte_array, format='bmp') + stdout_img_bytes: bytes = img_byte_array.getvalue() + sys.stdout.buffer.write(stdout_img_bytes) + + +if __name__ == '__main__': + parser = argparse.ArgumentParser() + parser.add_argument('-n', '--nostdin', default=True, action='store_false') + parser.add_argument('-i', '--image', default=None, required=False, type=str) + + args = parser.parse_args() + + main(args.nostdin, args.image) \ No newline at end of file diff --git a/tools/to_bitmap.py b/tools/to_bitmap.py index 3d2683e..215f9c8 100644 --- a/tools/to_bitmap.py +++ b/tools/to_bitmap.py @@ -10,24 +10,30 @@ from io import BytesIO from PIL import Image -def main() -> None: +def processing(image: Image) -> Image: + image = image.resize((128, 64), Image.LANCZOS) # Resize to 128x64 or 128x62 [pixels]. Lanczos interpolation for best result + image = image.convert('1') # Convert to 1 bit black/white + + return image + + +def main(): """ Get input image as raw bytes """ - stdin_img_bytes: ByteIO = BytesIO(sys.stdin.buffer.read()) + stdin_img_bytes = BytesIO(sys.stdin.buffer.read()) """ Processing """ - img: Image = Image.open(stdin_img_bytes) - img: Image = img.convert('LA') # Convert to grayscale - img: Image = img.resize((128, 64), Image.LANCZOS) # Resize to 128x64 or 128x62 [pixels]. Lanczos interpolation for best result + img = Image.open(stdin_img_bytes) + img = processing(img) """ Saving image into ByteIO object """ - img_byte_array: BytesIO = BytesIO() - img.save(img_byte_array, format = 'png') + img_byte_array = BytesIO() + img.save(img_byte_array, format='bmp') """ Getting bytes (array of bytes)