Martin Valik 5 лет назад
Родитель
Сommit
8863a7b36d

+ 4 - 0
CMakeLists.txt

@@ -20,6 +20,10 @@ else()
     if(PORT STREQUAL "STM32")
     if(PORT STREQUAL "STM32")
         target_link_libraries(flasher PUBLIC stm_cube)
         target_link_libraries(flasher PUBLIC stm_cube)
         target_sources(flasher PRIVATE port/stm32_port.c)
         target_sources(flasher PRIVATE port/stm32_port.c)
+    elseif(PORT STREQUAL "RASPBERRY_PI")
+        find_library(pigpio_LIB pigpio)
+        target_link_libraries(flasher PUBLIC ${pigpio_LIB})
+        target_sources(flasher PRIVATE port/raspberry_port.c)
     else()
     else()
         message(FATAL_ERROR "Selected port is not supported")
         message(FATAL_ERROR "Selected port is not supported")
     endif()
     endif()

+ 36 - 0
examples/raspberry_example/CMakeLists.txt

@@ -0,0 +1,36 @@
+cmake_minimum_required(VERSION 3.5)
+
+# Creates C resources file from files in given directory
+function(create_resources dir output)
+    # Create empty output file
+    file(WRITE ${output} "")
+    # Collect input files
+    file(GLOB bins ${dir}/*)
+    # Iterate through input files
+    foreach(bin ${bins})
+        # Get short filenames
+        string(REGEX MATCH "([^/]+)$" filename ${bin})
+        message(STATUS "filename: " ${filename})
+        # Replace filename spaces & extension separator for C compatibility
+        string(REGEX REPLACE "\\.| |-" "_" filename ${filename})
+        # Read hex data from file
+        file(READ ${bin} filedata HEX)
+        # Convert hex data for C compatibility
+        string(REGEX REPLACE "([0-9a-f][0-9a-f])" "0x\\1," filedata ${filedata})
+        # Append data to output file
+        file(APPEND ${output} "const unsigned char ${filename}[] = {${filedata}};\nconst unsigned ${filename}_size = sizeof(${filename});\n")
+    endforeach()
+endfunction()
+
+set(FLASHER_DIR ${CMAKE_CURRENT_LIST_DIR}/../..)
+set(PORT RASPBERRY_PI)
+
+project(raspberry_flasher)
+    
+create_resources(images Src/binaries.c)
+
+add_executable(${CMAKE_PROJECT_NAME} Src/main.c Src/binaries.c)
+
+add_subdirectory(${FLASHER_DIR} ${CMAKE_BINARY_DIR}/flasher)
+
+target_link_libraries(${CMAKE_PROJECT_NAME} PRIVATE flasher)

+ 76 - 0
examples/raspberry_example/README.md

@@ -0,0 +1,76 @@
+# Raspberry Pi example
+
+## Overview
+
+Example demonstrates how to flash ESP32 from Raspberry Pi 4 (Model B) using esp_serial_flash component API. Binaries to be flashed from Raspberry Pi to ESP32 can be found in `images` directory and converted into C-arrays during build process. USART0 is dedicated for communication with ESP32.
+
+Following steps are performed in order to re-program target's memory:
+
+1. Peripherals are initialized.
+2. Host puts slave device into boot mode tries to connect by calling `esp_loader_connect()`.
+3. Then `esp_loader_flash_start()` is called to enter flashing mode and erase amount of memory to be flashed.
+4. `esp_loader_flash_write()` function is called repeatedly until the whole binary image is transfered.
+5. At the end, `loader_port_reset_target()` is called to restart ESP32 and execute updated firmware.
+
+Note: In addition, to steps mentioned above, `esp_loader_change_baudrate`  is called after connection is established in order to increase flashing speed. Bootloader is also capable of detecting baud rate during connection phase, and can be changed before calling `esp_loader_connect`. However, it is recommended to start at lower speed and then use dedicated command to increase baud rate. This does not apply for ESP8266, as its bootloader does not support this command, therefore, baud rate can only be changed before connection phase in this case.
+
+## Hardware Required
+
+* Raspberry Pi 4 Model B. 
+* A development board with ESP32 SoC (e.g. ESP-WROVER-KIT, ESP32-DevKitC, etc.).
+* USB cable in case ESP32 board is powered from USB. ESP32 can be powered by Raspberry Pi as well.
+
+## Hardware connection
+
+Table below shows connection between Raspberry Pi and ESP32.
+
+| Raspberry Pi (host) |    ESP32 (slave)    |
+|:-------------------:|:-------------------:|
+|        GPIO3        |         IO0         |
+|        GPIO2        |         RST         |
+|        GPIO14       |         RX0         |
+|        GPIO15       |         TX0         |
+|         GND         |         GND         |
+
+Optionally, UART-to-USB bridge can be connected to PD5(RX) and PD6(TX) for debug purposes.
+
+## Installation
+
+### GPIO library
+Raspberry Pi makes use of [pigpio](http://abyz.me.uk/rpi/pigpio/) library in order to simplify controlling GPIO pins. Some distributions of 'Raspberry Pi OS' may come with `pigpio` already installed. Presence of the library in the system can checked by running command:
+```
+pigpiod -v
+```
+
+If not present, run following commands to install the library. 
+```
+sudo apt-get update
+sudo apt-get install pigpio
+```
+
+### Enable UART
+On Raspberry Pi 4, primary UART (UART0) is connected to the On-board Bluetooth module by default.
+In order to enable serial communication on this UART, run following command in terminal:
+```
+sudo raspi-config
+```
+
+* Navigate to **Interfacing Options -> Serial**.
+* Then it will ask for login shell to be accessible over Serial, select **No**.
+* After that, it will ask for enabling Hardware Serial port, select **Yes**.
+* Reboot the Raspberry Pi.
+
+## Build and run
+
+To compile the example:
+
+Create and navigate to `build` directory:
+```
+mkdir build && cd build
+```
+Run cmake, build example and run example: 
+```
+cmake .. && cmake --build . && ./raspberry_flasher
+```
+
+For more details regarding to esp_serial_flasher configuration, please refer to top level [README.md](../../README.md).

+ 124 - 0
examples/raspberry_example/Src/main.c

@@ -0,0 +1,124 @@
+/* Flash multiple partitions example
+
+   This example code is in the Public Domain (or CC0 licensed, at your option.)
+
+   Unless required by applicable law or agreed to in writing, this
+   software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
+   CONDITIONS OF ANY KIND, either express or implied.
+*/
+
+#include <stdio.h>
+#include <stdint.h>
+#include <string.h>
+#include <sys/param.h>
+#include "serial_io.h"
+#include "esp_loader.h"
+
+#define TARGET_RST_Pin 2
+#define TARGET_IO0_Pin 3
+
+#define DEFAULT_BAUD_RATE 115200
+#define HIGHER_BAUD_RATE  460800
+#define SERIAL_DEVICE     "/dev/ttyS0"
+
+esp_loader_error_t loader_port_rpi_init(const char *device,
+                                        uint32_t baudrate,
+                                        uint32_t reset_trigger_pin,
+                                        uint32_t gpio0_trigger_pin);
+
+extern const unsigned char bootloader_bin[];
+extern const unsigned bootloader_bin_size;
+extern const unsigned char hello_world_bin[];
+extern const unsigned hello_world_bin_size;
+extern const unsigned char partition_table_bin[];
+extern const unsigned partition_table_bin_size;
+
+const uint32_t BOOTLOADER_ADDRESS  = 0x1000;
+const uint32_t PARTITION_ADDRESS   = 0x8000;
+const uint32_t APPLICATION_ADDRESS = 0x10000;
+
+
+esp_loader_error_t flash_binary(const unsigned char *bin, size_t size, size_t address)
+{
+    esp_loader_error_t err;
+    int32_t packet_number = 0;
+    static uint8_t payload[1024];
+    const unsigned char *bin_addr = bin;
+
+    printf("Erasing flash...\n");
+    err = esp_loader_flash_start(address, size, sizeof(payload));
+    if (err != ESP_LOADER_SUCCESS) {
+        printf("Erasing flash failed with error %d.\n", err);
+        return err;
+    }
+    printf("Start programming\n");
+
+    while (size > 0) {
+        size_t to_read = MIN(size, sizeof(payload));
+        memcpy(payload, bin_addr, to_read);
+
+        err = esp_loader_flash_write(payload, to_read);
+        if (err != ESP_LOADER_SUCCESS) {
+            printf("Packet could not be written\n");
+            return err;
+        }
+
+        printf("packet: %ld  written: %u B\n", packet_number++, to_read);
+
+        size -= to_read;
+        bin_addr += to_read;
+    };
+
+    printf("Finished programming\n");
+
+#if MD5_ENABLED
+    err = esp_loader_flash_verify();
+    if (err != ESP_LOADER_SUCCESS) {
+        printf("MD5 does not match. err: %d\n", err);
+        return err;
+    }
+    printf("Flash verified\n");
+#endif
+
+    return ESP_LOADER_SUCCESS;
+}
+
+esp_loader_error_t connect_to_target()
+{
+    loader_port_rpi_init(SERIAL_DEVICE, DEFAULT_BAUD_RATE, TARGET_RST_Pin, TARGET_IO0_Pin);
+
+    esp_loader_connect_args_t connect_config = ESP_LOADER_CONNECT_DEFAULT();
+
+    esp_loader_error_t err = esp_loader_connect(&connect_config);
+    if (err != ESP_LOADER_SUCCESS) {
+        printf("Cannot connect to target. Error: %u\n", err);
+        return err;
+    }
+    printf("Connected to target\n");
+
+    err = esp_loader_change_baudrate(HIGHER_BAUD_RATE);
+    if (err != ESP_LOADER_SUCCESS) {
+        printf("Unable to change baud rate on target.\n");
+        return err;
+    }
+
+    err = loader_port_change_baudrate(HIGHER_BAUD_RATE);
+    if (err != ESP_LOADER_SUCCESS) {
+        printf("Unable to change baud rate.\n");
+        return err;
+    }
+    printf("Baudrate changed\n");
+
+    return ESP_LOADER_SUCCESS;
+}
+
+int main(void)
+{
+    if (connect_to_target() == ESP_LOADER_SUCCESS) {
+        flash_binary(bootloader_bin, bootloader_bin_size, BOOTLOADER_ADDRESS);
+        flash_binary(partition_table_bin, partition_table_bin_size, PARTITION_ADDRESS);
+        flash_binary(hello_world_bin, hello_world_bin_size, APPLICATION_ADDRESS);
+    }
+
+    loader_port_reset_target();
+}

BIN
examples/raspberry_example/images/bootloader.bin


BIN
examples/raspberry_example/images/hello-world.bin


BIN
examples/raspberry_example/images/partition-table.bin


+ 2 - 1
include/esp_loader.h

@@ -32,7 +32,8 @@ typedef enum
     ESP_LOADER_ERROR_FAIL,             /*!< Unspecified error */
     ESP_LOADER_ERROR_FAIL,             /*!< Unspecified error */
     ESP_LOADER_ERROR_TIMEOUT,          /*!< Timeout elapsed */
     ESP_LOADER_ERROR_TIMEOUT,          /*!< Timeout elapsed */
     ESP_LOADER_ERROR_IMAGE_SIZE,       /*!< Image size to flash is larger than flash size */
     ESP_LOADER_ERROR_IMAGE_SIZE,       /*!< Image size to flash is larger than flash size */
-    ESP_LOADER_ERROR_INVALID_MD5,      /*!< Computed and receied MD5 does not match */
+    ESP_LOADER_ERROR_INVALID_MD5,      /*!< Computed and received MD5 does not match */
+    ESP_LOADER_ERROR_INVALID_PARAM,    /*!< Invalid parameter passed to function */
     ESP_LOADER_ERROR_INVALID_TARGET,   /*!< Connected target is invalid */
     ESP_LOADER_ERROR_INVALID_TARGET,   /*!< Connected target is invalid */
     ESP_LOADER_ERROR_UNSUPPORTED_CHIP, /*!< Attached chip is not supported */
     ESP_LOADER_ERROR_UNSUPPORTED_CHIP, /*!< Attached chip is not supported */
     ESP_LOADER_ERROR_INVALID_RESPONSE  /*!< Internal error */
     ESP_LOADER_ERROR_INVALID_RESPONSE  /*!< Internal error */

+ 309 - 0
port/raspberry_port.c

@@ -0,0 +1,309 @@
+/* Copyright 2020 Espressif Systems (Shanghai) PTE LTD
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *     http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#include "serial_io.h"
+#include "serial_comm.h"
+#include <pigpio.h>
+
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <termios.h>
+#include <time.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <stdarg.h>
+#include <sys/ioctl.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <sys/param.h>
+
+// #define SERIAL_DEBUG_ENABLE
+
+#ifdef SERIAL_DEBUG_ENABLE
+
+static void serial_debug_print(const uint8_t *data, uint16_t size, bool write)
+{
+    static bool write_prev = false;
+    uint8_t hex_str[3];
+
+    if (write_prev != write) {
+        write_prev = write;
+        printf("\n--- %s ---\n", write ? "WRITE" : "READ");
+    }
+
+    for (uint32_t i = 0; i < size; i++) {
+        printf("%02x ", data[i]);
+    }
+}
+
+#else
+
+static void serial_debug_print(const uint8_t *data, uint16_t size, bool write) { }
+
+#endif
+
+static int serial;
+static int64_t s_time_end;
+static int32_t s_reset_trigger_pin;
+static int32_t s_gpio0_trigger_pin;
+
+
+static speed_t convert_baudrate(int baud)
+{
+    switch (baud) {
+        case 50: return B50;
+        case 75: return B75;
+        case 110: return B110;
+        case 134: return B134;
+        case 150: return B150;
+        case 200: return B200;
+        case 300: return B300;
+        case 600: return B600;
+        case 1200: return B1200;
+        case 1800: return B1800;
+        case 2400: return B2400;
+        case 4800: return B4800;
+        case 9600: return B9600;
+        case 19200: return B19200;
+        case 38400: return B38400;
+        case 57600: return B57600;
+        case 115200: return B115200;
+        case 230400: return B230400;
+        case 460800: return B460800;
+        case 500000: return B500000;
+        case 576000: return B576000;
+        case 921600: return B921600;
+        case 1000000: return B1000000;
+        case 1152000: return B1152000;
+        case 1500000: return B1500000;
+        case 2000000: return B2000000;
+        case 2500000: return B2500000;
+        case 3000000: return B3000000;
+        case 3500000: return B3500000;
+        case 4000000: return B4000000;
+        default: return -1;
+    }
+}
+
+static int serialOpen (const char *device, uint32_t baudrate)
+{
+    struct termios options;
+    int status, fd;
+
+    if ((fd = open (device, O_RDWR | O_NOCTTY | O_NDELAY | O_NONBLOCK)) == -1) {
+        printf("Error occured while opening serial port !\n");
+        return -1 ;
+    }
+
+    fcntl (fd, F_SETFL, O_RDWR) ;
+
+    // Get and modify current options:
+
+    tcgetattr (fd, &options);
+    speed_t baud = convert_baudrate(baudrate);
+
+    if(baud < 0) {
+        printf("Invalid baudrate!\n");
+        return -1;
+    }
+
+    cfmakeraw   (&options) ;
+    cfsetispeed (&options, baud) ;
+    cfsetospeed (&options, baud) ;
+
+    options.c_cflag |= (CLOCAL | CREAD) ;
+    options.c_cflag &= ~(PARENB | CSTOPB | CSIZE) ;
+    options.c_cflag |= CS8 ;
+    options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG) ;
+    options.c_oflag &= ~OPOST ;
+    options.c_iflag &= ~(IXON | IXOFF | IXANY); // Turn off s/w flow ctrl
+    options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL); // Disable any special handling of received bytes
+
+    options.c_cc [VMIN]  = 0 ;
+    options.c_cc [VTIME] = 10 ; // 1 Second
+
+    tcsetattr (fd, TCSANOW, &options) ;
+
+    ioctl (fd, TIOCMGET, &status);
+
+    status |= TIOCM_DTR ;
+    status |= TIOCM_RTS ;
+
+    ioctl (fd, TIOCMSET, &status);
+
+    usleep (10000) ;  // 10mS
+
+    return fd ;
+}
+
+static esp_loader_error_t change_baudrate(int file_desc, int baudrate)
+{
+    struct termios options;
+    speed_t baud = convert_baudrate(baudrate);
+
+    if(baud < 0) {
+        return ESP_LOADER_ERROR_INVALID_PARAM;
+    }
+
+    tcgetattr (file_desc, &options);
+
+    cfmakeraw   (&options) ;
+    cfsetispeed (&options, baud);
+    cfsetospeed (&options, baud);
+
+    tcsetattr (file_desc, TCSANOW, &options);
+
+    return ESP_LOADER_SUCCESS; 
+}
+
+static void set_timeout(uint32_t timeout)
+{
+    struct termios options;
+
+    timeout /= 100;
+    timeout = MAX(timeout, 1);
+
+    tcgetattr(serial, &options);
+    options.c_cc[VTIME] = timeout;
+    tcsetattr(serial, TCSANOW, &options);
+}
+
+static esp_loader_error_t read_char(char *c, uint32_t timeout)
+{
+    set_timeout(timeout);
+    int read_bytes = read(serial, c, 1);
+
+    if (read_bytes == 1) {
+        return ESP_LOADER_SUCCESS;
+    } else if (read_bytes == 0) {
+        return ESP_LOADER_ERROR_TIMEOUT;
+    } else {
+        return ESP_LOADER_ERROR_FAIL;
+    }
+}
+
+static esp_loader_error_t read_data(char *buffer, uint32_t size)
+{
+    for (int i = 0; i < size; i++) {
+        uint32_t remaining_time = loader_port_remaining_time();
+        RETURN_ON_ERROR( read_char(&buffer[i], remaining_time) );
+    }
+
+    return ESP_LOADER_SUCCESS;
+}
+
+esp_loader_error_t loader_port_rpi_init(const char *device,
+                                        uint32_t baudrate,
+                                        uint32_t reset_trigger_pin,
+                                        uint32_t gpio0_trigger_pin)
+{
+    s_reset_trigger_pin = reset_trigger_pin;
+    s_gpio0_trigger_pin = gpio0_trigger_pin;
+
+    serial = serialOpen(device, baudrate);
+    if (serial < 0) {
+        printf("Serial port could not be opened!\n");
+        return ESP_LOADER_ERROR_FAIL;
+    }
+
+    if (gpioInitialise() < 0) {
+        printf("pigpio initialisation failed\n");
+        return ESP_LOADER_ERROR_FAIL;
+    }
+
+    gpioSetMode(reset_trigger_pin, PI_OUTPUT);
+    gpioSetMode(gpio0_trigger_pin, PI_OUTPUT);
+
+    return ESP_LOADER_SUCCESS;
+}
+
+
+esp_loader_error_t loader_port_serial_write(const uint8_t *data, uint16_t size, uint32_t timeout)
+{
+    serial_debug_print(data, size, true);
+
+    int written = write(serial, data, size);
+
+    if (written < 0) {
+        return ESP_LOADER_ERROR_FAIL;
+    } else if (written < size) {
+        return ESP_LOADER_ERROR_TIMEOUT;
+    } else {
+        return ESP_LOADER_SUCCESS;
+    }
+}
+
+
+esp_loader_error_t loader_port_serial_read(uint8_t *data, uint16_t size, uint32_t timeout)
+{
+    RETURN_ON_ERROR( read_data(data, size) );
+
+    serial_debug_print(data, size, false);
+
+    return ESP_LOADER_SUCCESS;
+}
+
+
+// Set GPIO0 LOW, then assert reset pin for 50 milliseconds.
+void loader_port_enter_bootloader(void)
+{
+    gpioWrite(s_gpio0_trigger_pin, 0);
+    gpioWrite(s_reset_trigger_pin, 0);
+    loader_port_delay_ms(50);
+    gpioWrite(s_reset_trigger_pin, 1);
+    loader_port_delay_ms(50);
+    gpioWrite(s_gpio0_trigger_pin, 1);
+}
+
+
+void loader_port_reset_target(void)
+{
+    gpioWrite(s_reset_trigger_pin, 0);
+    loader_port_delay_ms(50);
+    gpioWrite(s_reset_trigger_pin, 1);
+}
+
+
+void loader_port_delay_ms(uint32_t ms)
+{
+    usleep(ms * 1000);
+}
+
+
+void loader_port_start_timer(uint32_t ms)
+{
+    s_time_end = clock() + (ms * (CLOCKS_PER_SEC / 1000));
+}
+
+
+uint32_t loader_port_remaining_time(void)
+{
+    int64_t remaining = (s_time_end - clock()) / 1000;
+    return (remaining > 0) ? (uint32_t)remaining : 0;
+}
+
+
+void loader_port_debug_print(const char *str)
+{
+    printf("DEBUG: %s\n", str);
+}
+
+esp_loader_error_t loader_port_change_baudrate(uint32_t baudrate)
+{
+    return change_baudrate(serial, baudrate);
+}