Giter VIP home page Giter VIP logo

hulp's Introduction

HULP

HULP is a helper library for the ESP32's Ultra Low Power Co-Processor (ULP).


Features

Memory Access

Easily access variables to store and retrieve data, or share between the ULP and SoC

RTC_SLOW_ATTR ulp_var_t my_ulp_variable;

// ULP:
I_MOVI(R2, 0),
I_GET(R1, R2, my_ulp_variable), // Load my_ulp_variable into R1
I_PUT(R3, R2, my_ulp_variable), // Store R3 into my_ulp_variable

// SoC:
uint16_t temp = my_ulp_variable.val;
my_ulp_variable.val = 123;

GPIO

Functions to configure GPIOs in preparation for the ULP

hulp_configure_pin(GPIO_NUM_25, RTC_GPIO_MODE_INPUT_ONLY, GPIO_PULLUP_ONLY, 0);
hulp_configure_pin(GPIO_NUM_26, RTC_GPIO_MODE_OUTPUT_ONLY, GPIO_FLOATING, 1);
hulp_configure_analog_pin(GPIO_NUM_33, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12);

Countless macros to simplify ULP GPIO operations

I_GPIO_READ(GPIO_NUM_27),       // Digital read
I_GPIO_SET(GPIO_NUM_25, 1),     // Set digital output level high
I_ANALOG_READ(R0, GPIO_NUM_33), // Analog read
I_GPIO_PULLUP(GPIO_NUM_26, 1),  // Enable internal pullup

As well as advanced functionality, including interrupts

// Configure edge interrupt:
hulp_configure_pin_int(GPIO_NUM_32, GPIO_INTR_ANYEDGE);
// ULP:
I_GPIO_INT_RD(GPIO_NUM_32),   // Check if interrupt has triggered
I_GPIO_INT_CLR(GPIO_NUM_32),  // Clear interrupt

Timing

Macros for basic delays

M_DELAY_US_10_100(72),    // Delay 72uS
M_DELAY_MS_20_1000(500),  // Delay 500mS

HULP also introduces a concept that makes use of the RTC slow clock for complex, asynchronous timing operations, useful for very power efficient operation and multitasking without the need for blocking delays. See Timing example.

Peripherals

Helpers and drivers for internal peripherals as well as communication protocols, including:

  • Capacitive Touch

  • Hall Effect

  • Temperature

  • Hardware I2C

  • Software (bitbanged) I2C

  • APA RGB LED

  • UART

  • HX711

Debugging

  • Insert breakpoints, track and manipulate ULP program flow, inspect or alter register contents via the SoC

  • Combine the UART driver with included ULP PRINTF subroutines to communicate debugging information independent of the SoC (even in deep sleep!)

And much more...

Check out the examples for some programs demonstrating the possibilities of the ULP with HULP.

There's a lot more to HULP than what is mentioned above - in lieu of better documentation, please see relevant header files for more features and information.


Compatibility

HULP uses the C macro (legacy) programming method (https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-guides/ulp_macros.html), however you are free to copy and convert any parts for use with the ULP binary toolchain.

ESP-IDF >=4.2.0 is required, and there is partial support for Arduino-ESP32 >=2.0.0.

Only ESP32 is currently supported.

hulp's People

Contributors

boarchuz avatar johnboiles avatar will-emmerson avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

hulp's Issues

problems reading sht3x i2c sensor

Thanks for making this amazing library, I had previously put off using the ULP because I don't really know assembly but using this I think it might be possible. Having said that, I am struggling to read from a sht3x sensor which requires a write of 2 bytes and a read of 6 bytes. I have created the following by piecing together examples there are no interupts firing in the app, unlike the simpler i2c examples:

#define SCL_PIN GPIO_NUM_26
#define SDA_PIN GPIO_NUM_25

#define SLAVE_ADDR 0x0
#define SLAVE_REG 0x44

RTC_SLOW_ATTR ulp_var_t ulp_write_cmd[] = {
        HULP_I2C_CMD_HDR(SLAVE_ADDR, SLAVE_REG, 2),
        HULP_I2C_CMD_2B(0x24, 0x00),
};
RTC_SLOW_ATTR ulp_var_t ulp_read_cmd[HULP_I2C_CMD_BUF_SIZE(6)] = {
        HULP_I2C_CMD_HDR(SLAVE_ADDR, SLAVE_REG, 6),
};

gpio_num_t LED_ERR = GPIO_NUM_13;

void init_ulp() {
    enum {
        LABEL_I2C_READ,
        LABEL_I2C_READ_RETURN,
        LABEL_I2C_WRITE,
        LABEL_I2C_WRITE_RETURN,
        LABEL_I2C_ERROR
    };

    const ulp_insn_t program[] = {

            // write 2 bytes
            I_MOVO(R1, ulp_write_cmd),
            M_MOVL(R3, LABEL_I2C_WRITE_RETURN),
            M_BX(LABEL_I2C_WRITE),
            M_LABEL(LABEL_I2C_WRITE_RETURN),
            M_BGE(LABEL_I2C_ERROR, 1),

            // delay 20ms
            M_DELAY_MS_20_1000(20),

            // read 6 bytes
            I_MOVO(R1, ulp_read_cmd),
            M_MOVL(R3, LABEL_I2C_READ_RETURN),
            M_BX(LABEL_I2C_READ),
            M_LABEL(LABEL_I2C_READ_RETURN),
            M_BGE(LABEL_I2C_ERROR, 1),

            // notify change and exit
            I_WAKE(),
            I_HALT(),

            M_LABEL(LABEL_I2C_ERROR),
            I_GPIO_SET(LED_ERR, 1),
            I_END(),

            M_INCLUDE_I2CBB_CMD(LABEL_I2C_READ, LABEL_I2C_WRITE, SCL_PIN, SDA_PIN)
    };

    ESP_ERROR_CHECK(hulp_configure_pin(SCL_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_FLOATING, 0));
    ESP_ERROR_CHECK(hulp_configure_pin(SDA_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_FLOATING, 0));

    hulp_peripherals_on();

    vTaskDelay(1000 / portTICK_PERIOD_MS);

    ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 1ULL * 1000 * 1000, 0));
    ESP_ERROR_CHECK(hulp_ulp_run(0));
}

I've tried to copy the I2CBB_CMD example in the documentation but that only does a single read. The sensor definitely works and the following normal i2c code returns a value:

    i2c_init(GPIO_NUM_25, GPIO_NUM_26);

    uint8_t out[] = {0x24, 0x00};
    i2c_write(SLAVE_REG, out, 2);

    vTaskDelay(pdMS_TO_TICKS(10));

    #define in_len 6
    uint8_t in[in_len] = {};
    i2c_read(SLAVE_REG, in, in_len);

I've also tried RTC_GPIO_MODE_INPUT_OUTPUT but that doesn't work either.

Add librairies in Arduino ide

@boarchuz Firstly, thank you so much for creating this library - it looks very good !

I'm triing to build a raingauge with an esp32 to count if it is raining.
I can't find the librairie in the Arduino Ide, I tried with zip file but it is not working

Can you help me on this ?

Thank you again

I2C bitbang example gpio question

Hello @boarchuz, thanks a lot for the great lib! I used it in some my project, appreciate it!

I've issue with I2C bitbang example. SCL, SDA pins are not toggled yet. I use esp32 classic SoC, pins 13, 14 as at the example. Pullup resistor connected to 3.3V power line. BTW when I did try blinking example the same pins works fine.

Main difference is pin setup:
I2C bitbang code uses: RTC_GPIO_MODE_INPUT_ONLY
ESP_ERROR_CHECK(hulp_configure_pin(SCL_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_FLOATING, 0));
but blinking example uses: RTC_GPIO_MODE_OUTPUT_ONLY
ESP_ERROR_CHECK(hulp_configure_pin(SCL_PIN, RTC_GPIO_MODE_OUTPUT_ONLY, GPIO_FLOATING, 0));

I see that bitbang code uses different pin control with:
I_GPIO_OUTPUT_EN(scl_gpio)
I_GPIO_OUTPUT_DIS(scl_gpio)

but blinking code uses:
I_GPIO_SET(scl_gpio,1)
I_GPIO_SET(scl_gpio,0)

BTW, I use android/platformio framework, may it be cause of issue?

Thanks and Regards,
Sergey

How to loop through a byte array and set the gpio

I was the one who was asking on discord on how to bitbang a 125 kbit/sec bus. As I mentioned one byte is transferred as 10 bits because after the 4th and 8th bits there is a bit stuffed which is the opposite of the previous one. To transmit on the bus we need to wait at least 16 bits of high state (16 * 8us). After that we can start transferring, but if we send a high state and we read back a low state on the rx line we need to stop transferring immediately as someone else also is transmitting with higher priority. Also we don't care if we sent a low, but receive a high, that is fine, we can continue.

You suggested to check the ULP coprocessor.
After doing some research I found your awesome library. I checked the examples but some things aren't obvious for the first (few) reads.
I settled with the ULPAPADriver as that seems the most complex one which has most of the parts I need.
Based on that I prepared a library for my use-case, but I am kind of stuck on how to transmit the bits of a byte. I think I managed to write the part where I wait to start transmitting, but I just can't understand how to loop through my data array and write the bits onto the gpio.

Can you take a look and give me a hint how to proceed further?

Here is the code on the main CPU

#include <arduino.h>
#include <hulp_arduino.h>
#include <stdint.h>
#include "UlpVanDriver.h"

#define VAN_RX_PIN GPIO_NUM_12
#define VAN_TX_PIN GPIO_NUM_13

ULPVANData ulpdata[40]; // 255 bits
UlpVanDriver ulpVanDriver(ulpdata, VAN_RX_PIN, VAN_TX_PIN);

void setup()
{
    ulpVanDriver.InitGpio();
}

void loop()
{
    //I do the bitstuffing here
    ulpVanDriver.ConvertByteToUlpData(0x0E, &ulpdata[0]);
    ulpVanDriver.ConvertByteToUlpData(0x5E, &ulpdata[1]);
    ulpVanDriver.ConvertByteToUlpData(0x4C, &ulpdata[2]);

    ulpVanDriver.ConvertByteToUlpData(0x20, &ulpdata[3]);
    ulpVanDriver.ConvertByteToUlpData(0x1E, &ulpdata[4]);

    ulpVanDriver.ConvertByteToUlpData(0x8A, &ulpdata[5]);
    ulpVanDriver.ConvertByteToUlpData(0x50, &ulpdata[6]);
    //EOD signaled with e-manchester violation
    ulpdata[6].manchester_bit9 = 0;

    //2 bit ACK + End of frame
    ulpdata[7].lower_nibble = 0xFF;
    ulpdata[7].manchester_bit4 = 1;
    ulpdata[7].upper_nibble = 0xFF;
    ulpdata[7].manchester_bit9 = 1;

   //and signal the ULP coprocessor that it can transfer
    ulpVanDriver.SendFrame(8);
    delay(2000);
}

And here is my ULP code:

#define ULPVANData RTC_SLOW_ATTR WORD_ALIGNED_ATTR ulp_van_byte_t

struct ulp_van_byte_t {
    uint32_t lower_nibble    : 4;  // 0-3
    uint32_t manchester_bit4 : 1;  // 4
    uint32_t upper_nibble    : 4;  // 5-8
    uint32_t manchester_bit9 : 1;  // 9

    uint32_t command_type    : 5;  // 10-14   /*!< 1: normal frame, 2: query frame, 3: ack only */
    uint32_t transmit_data   : 1;  // 15      /*!< Bit for SoC to flag ULP to transmit */

    uint32_t upper1          : 16; // 16-31    /*!< 16 bits inaccessible to ULP */


    uint32_t message_length : 8;   // 0-7      /*!< length of the message */
    uint32_t unused         : 8;   // 8-15     /*!<  */

    uint32_t upper2         : 16;  // 16-31    /*!< 16 bits inaccessible to ULP */
};

UlpVanDriver::UlpVanDriver(ulp_van_byte_t *vanData, gpio_num_t rxPin, gpio_num_t txPin)
{
    _vanData = vanData;
    _rxPin = rxPin;
    _txPin = txPin;

    #define VAN_DATA_ARR_OFFSET (((uint32_t)_vanData - ((uint32_t)RTC_SLOW_MEM)) / 4)

    enum {
        LABEL_POLL,
        LABEL_CHECK_IDLE,
        LABEL_TX_BIT,
    };

    const ulp_insn_t ulpProgram[] = {

    //Reset Pointer
    I_MOVI(R1, VAN_DATA_ARR_OFFSET),

    //Set a register to 0 for use with I_GET and I_PUT
    I_MOVI(R2, 0),

    //Wait here until SoC sets flag to transmit
    I_LD(R0,R1,0),
    I_BL(-1, 1 << 15),

    //Clear the flag
    I_ANDI(R0,R0,0x7FFF),
    I_ST(R0,R1,0),

    M_LABEL(LABEL_POLL),
        //While the GPIO is low, continue polling the pin
        I_GPIO_READ(_rxPin),
        I_BL(-1,1),

        //We have a high state, "move into the middle" of the bit
        M_DELAY_US_1_10(4),

        //Wait for 16 bits of high state to ensure the bus is idle (16 * 8us)
        I_STAGE_RST(),
        M_LABEL(LABEL_CHECK_IDLE),
            I_STAGE_INC(1),

            //Wait for 8us to "move into the next bit"
            M_DELAY_US_1_10(8),

            I_GPIO_READ(_rxPin),
            //If the GPIO is low, we need to wait for the bus to become idle again
            M_BL(LABEL_POLL, 1),

            M_BSLE(LABEL_CHECK_IDLE, 16),
            //We have 16 bits of high state, so we can start writing the data

        I_STAGE_RST(),
        M_LABEL(LABEL_TX_BIT),
            //this is where I should implement the loop which shifts out the bits based on the data in _vanData but I am not sure how to do that conditionally
            //vanData[0].message_length contains how many bytes my message have

            I_GPIO_SET(_txPin, 1),
            //I_DELAY() //should we wait a few ns to let the pin settle?

            //read back the GPIO to ensure it is high
            I_GPIO_READ(_rxPin),
            //If the GPIO is low, but we sent high, we stop the transfer immediately and wait for the bus to become idle again
            M_BL(LABEL_POLL, 1),

           //bit transmit success, go back to LABEL_TX_BIT

    };


    size_t programSize = sizeof(ulpProgram) / sizeof(ulp_insn_t);
    ESP_ERROR_CHECK(ulp_process_macros_and_load(0, ulpProgram, &programSize));
    // ESP_ERROR_CHECK(ulp_set_wakeup_period(x);
    ESP_ERROR_CHECK(ulp_run(0));
}

Variable gets a value as if the shift command had not been executed

This is my simple program in the infinite loop that only measures the voltage from the mains and saves the value in the variable ulp_vars.pin2.val. The problem is that at some undefined intervals but certainly under one second this variable gets a value as if the shift command had not been executed. This is a simplified example from the HULP library, and in that original example, I didn't notice anything like this happening. Does anyone have any idea why this is happening?


#define PIN_ADC_PIN2    GPIO_NUM_34

#define PIN2_OVERSAMPLE_SHIFT 3

RTC_DATA_ATTR struct {
  ulp_var_t pin2;
} ulp_vars;

void ulp_init()
{
  enum {
    LBL_PIN2_OVERSAMPLE_LOOP,
    LBL_LOOP,
  };

  const ulp_insn_t program[] = {

    M_LABEL(LBL_LOOP),
    I_STAGE_RST(),//
    I_MOVI(R0, 0),//These are just attempts to solve the problem.
    I_MOVI(R1, 0),//
    I_MOVI(R2, 0),//
    I_MOVI(R3, 0),
    M_LABEL(LBL_PIN2_OVERSAMPLE_LOOP),
    I_ANALOG_READ(R1, PIN_ADC_PIN2),
    I_ADDR(R0, R0, R1),
    I_STAGE_INC(1),
    M_BSLT(LBL_PIN2_OVERSAMPLE_LOOP, (1 << PIN2_OVERSAMPLE_SHIFT)),
    I_RSHI(R0, R0, PIN2_OVERSAMPLE_SHIFT),
    I_MOVI(R3, 0),
    I_PUT(R0, R3, ulp_vars.pin2),
    I_GPIO_SET(GPIO_NUM_14, 1),//This produces 1.43 uS pulse
    I_GPIO_SET(GPIO_NUM_14, 0),// for test, nothing else !
    I_DELAY(10),
    I_BXI(LBL_LOOP),

  };
  ESP_ERROR_CHECK(hulp_configure_pin(GPIO_NUM_14, RTC_GPIO_MODE_OUTPUT_ONLY, GPIO_FLOATING, 1));
  ESP_ERROR_CHECK(hulp_configure_analog_pin(PIN_ADC_PIN2, ADC_ATTEN_DB_11, ADC_WIDTH_BIT_12));
  //ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 1000UL * ULP_WAKEUP_INTERVAL_MS, 0));
  size_t size = sizeof(program) / sizeof(ulp_insn_t);
  ESP_ERROR_CHECK(ulp_process_macros_and_load(0, program, &size));
  ESP_ERROR_CHECK(hulp_ulp_run(0));
}

void setup()
{
  Serial.begin(115200);
  if (hulp_is_deep_sleep_wakeup())
  {
    Serial.print("Wakeup !");
  }
  else
  {
    ulp_init();
  }
}

void loop() {
  Serial.println(ulp_vars.pin2.val);
}```

Issue with Sleep of ULP

I came across this issue where the ULP does not go to sleep for the requested time. I used the M_SET_WAKEUP_PERIOD instruction to set the register index 1 to one minute( in micro seconds). And then selected the sleep cycle using I_SLEEP_CYCLE_SEL(1). But the ULP does not sleep for 1 min after the I_HALT and before rerunning the code.
Here is the Code:

const ulp_insn_t program[] = {
M_SET_WAKEUP_PERIOD (1, 60000000),
I_SLEEP_CYCLE_SEL(1),
I_I2C_READ(0, SLAVE_SUBADDR), // Reading a data from a slave
I_MOVI(R2,0),
I_PUT(R0, R2, data),
};

Any help would be appreciated!

I2C bitbang CRC third byte does not match

Great job implementing the I2C bitbang mode in ULP! Your repo deserves more stars.

I'm porting the C code of reading the Sensirion SDP8xx digital sensor to HULP I2C bitbang. I'm reading the sensor periodically in continuous mode. C code is proven to work right, and it's here https://github.com/dizcza/sdpsensor-esp-arduino/blob/master/sdpsensor.cpp

The issue happens with the third byte which is CRC according to the documentation. The read value does not match with the expected (only in ULP mode, works fine in plain C).

#include <esp_log.h>
#include <esp_sleep.h>
#include <freertos/FreeRTOS.h>
#include <freertos/task.h>
#include <hulp.h>
#include <hulp_i2cbb.h>

#include "sdpsensor.h"


static const char *TAG = "MAIN";

static const uint8_t SLAVE_ADDR = 0x25;
static const gpio_num_t SDA_PIN = GPIO_NUM_33;
static const gpio_num_t SCL_PIN = GPIO_NUM_32;

static RTC_SLOW_ATTR ulp_var_t ulp_read_cmd[HULP_I2C_CMD_BUF_SIZE(3)] = {
        HULP_I2C_CMD_HDR_NO_PTR(SLAVE_ADDR, 3),
};


void init_ulp() {
    enum {
        LABEL_I2C_READ,
        LABEL_I2C_READ_CONTINUOUS,
        LABEL_I2C_READ_RETURN,
        LABEL_I2C_WRITE,
        LABEL_I2C_ERROR,
    };

    const ulp_insn_t program[] = {
            M_LABEL(LABEL_I2C_READ_CONTINUOUS),
            M_DELAY_US_100_5000(1000),
            I_MOVO(R1, ulp_read_cmd),
            M_MOVL(R3, LABEL_I2C_READ_RETURN),
            M_BX(LABEL_I2C_READ),
            M_LABEL(LABEL_I2C_READ_RETURN),
            M_BGE(LABEL_I2C_ERROR, 1),
            M_BX(LABEL_I2C_READ_CONTINUOUS),

            M_LABEL(LABEL_I2C_ERROR),
            I_WAKE(),
            I_END(),                // end ulp program so it won't run again
            I_HALT(),

            M_INCLUDE_I2CBB_CMD(LABEL_I2C_READ, LABEL_I2C_WRITE, SCL_PIN, SDA_PIN)
    };

    ESP_ERROR_CHECK(hulp_configure_pin(SCL_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_FLOATING, 0));
    ESP_ERROR_CHECK(hulp_configure_pin(SDA_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_FLOATING, 0));

    hulp_peripherals_on();

    vTaskDelay(1000 / portTICK_PERIOD_MS);

    ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 10ULL * 1000, 0));
    ESP_ERROR_CHECK(hulp_ulp_run(0));
}


void print_result() {
    const int16_t dp = (int16_t) ulp_read_cmd[HULP_I2C_CMD_DATA_OFFSET].val;
    const uint8_t crc = ulp_read_cmd[HULP_I2C_CMD_DATA_OFFSET + 1].val_bytes[0];
    ESP_LOGI(TAG, "Diff pressure %3d CRC %3d expected %3d", dp, crc,  compute_crc((uint8_t*) &dp));
}

void app_main(void) {

    SDPSensor_I2C_GPIO i2c_gpio = {
            .addr = SLAVE_ADDR,
            .port = 0,
            .sda = SDA_PIN,
            .scl = SCL_PIN
    };
    
    // Init the sensor & start continuous mode
    SDPSensor_Init(&i2c_gpio, NULL);
    
    init_ulp();

    while (1) {
        vTaskDelay(pdMS_TO_TICKS(100));
        print_result();
    }
}

Logs

I (2943) MAIN: Diff pressure  -8 CRC   0 expected   2
I (3043) MAIN: Diff pressure   7 CRC   0 expected  47
I (3143) MAIN: Diff pressure   3 CRC   0 expected 172
I (3243) MAIN: Diff pressure   9 CRC   0 expected  66
I (3343) MAIN: Diff pressure   3 CRC   0 expected 172
I (3443) MAIN: Diff pressure   2 CRC   0 expected  88
I (3543) MAIN: Diff pressure 10751 CRC   0 expected  14   // 10751 looks fishy, need to investigate; probably due to unsynchonous read-write operations of the same memory block
I (3643) MAIN: Diff pressure   4 CRC   0 expected   2
I (3743) MAIN: Diff pressure  -5 CRC   0 expected  47
I (3843) MAIN: Diff pressure   0 CRC   0 expected 129
I (3943) MAIN: Diff pressure  -4 CRC   0 expected 129
I (4043) MAIN: Diff pressure  12 CRC   0 expected  53
I (4143) MAIN: Diff pressure   1 CRC   0 expected 117
I (4243) MAIN: Diff pressure  -3 CRC   0 expected 117
I (4343) MAIN: Diff pressure   1 CRC   0 expected 117
I (4443) MAIN: Diff pressure   4 CRC   0 expected   2

Would much appreciate if you provide any hint why this might happen.

I have several other questions but let's deal with this one first.

support for mpu6050

hello, do you have any plans to support the mpu6050 if not, maybe someone has ideas on how to make it work

ESP32 Not Waking On I_WAKE()

  #include <esp_log.h>
  #include <esp_sleep.h>
  #include <freertos/FreeRTOS.h>
  #include <freertos/task.h>
  #include <hulp.h>
  #include <hulp_i2cbb.h>
  
  static const char *TAG = "MAIN";
  
  static const gpio_num_t LED_ERR = GPIO_NUM_2;

  void init_ulp()
  {
      const ulp_insn_t program[] = {
          I_GPIO_SET(LED_ERR, 1),
          I_WAKE(),
          I_HALT(),
      };

    ESP_ERROR_CHECK(hulp_configure_pin(LED_ERR, RTC_GPIO_MODE_OUTPUT_ONLY, GPIO_PULLDOWN_ONLY, 0));

    hulp_peripherals_on();

    vTaskDelay(1000 / portTICK_PERIOD_MS);
  
      ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 1000 * 1000, 0));
      ESP_ERROR_CHECK(hulp_ulp_run(0));
   }
  
  extern "C" void app_main(void)
  {
      if (hulp_is_deep_sleep_wakeup())
      {
          ESP_LOGE("ESP-CORE-ULP", "WAKING FROM SLEEP");
          vTaskDelay(100 / portTICK_PERIOD_MS);
      }
      else
      {
          init_ulp();
      }

      ESP_LOGI(TAG, "Sleeping");
      vTaskDelay(100 / portTICK_PERIOD_MS);
      hulp_peripherals_on();
      ESP_ERROR_CHECK(esp_sleep_enable_ulp_wakeup());
      esp_deep_sleep_start();
  }

Esp32 not waking up after this simple code. The ulp code is executing only once and the led turns on. Any help is appreciated. Thank You.

ESP32-S2

Hi, what a great project!

Does it work with ESP32-S2 ULP ?

Thanks, keep it up, David.

RTC LOW Memory limit for platformio / arduino

Hello @boarchuz !
ULP uses RTC 8K SRAM, but looks like platfmormio (arduino) build has small limit:

E (1052) ulp: program too big: 129 words, max is 128 words
E (1053) HULP: [hulp_ulp_load] load error (0x1201)
ESP_ERROR_CHECK failed: esp_err_t 0x1201 (ESP_ERR_ULP_SIZE_TOO_BIG) at 0x4008820c

I see that similar problem was fixed before, but maybe not for my configuration

my platformio.ini:
[env:esp32dev]
board = esp32dev
framework = arduino
platform = espressif32

Note: works well if

framework = espidf
and at sdconfig.defaults:
CONFIG_ESP32_ULP_COPROC_ENABLED=y
CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=1024

Question: how many time to start the ESP3 core from ULP interrupt ?

Hello,
I deveopp an application that receive infra red slave.
I would like to know if the TSOP (infra red receiver) Can start the ESP32 via ulp and if the ESP32 will be able to decode the infra red trame ?

I can send the infra red trame 3 times with a small time between.
Do ou think it is reallistic to wake up the ESP32 by the ULP and decode the trame ?
Is ther some example to wake up the ESP32 by the way of the ULP GPIO ?

Many thanks for your help.

ADC ULP

hi, i would like to know if you have done a code for taking measures with the ADC. Thanks

issue with I_GPIO_HOLD_DIS

So, this macro, which i try to call from the default wake stub, causes compile error

C:/Users/xxxxl/.platformio/packages/framework-espidf/components/ulp/include/esp32/ulp.h:347:5: error: expected primary-expression before '.' token
     .wr_reg = {\  

C:/Users/xxxx/.platformio/packages/framework-espidf/components/ulp/include/esp32/ulp.h:375:39: note: in expansion of macro 'I_WR_REG'
 #define I_WR_REG_BIT(reg, shift, val) I_WR_REG(reg, shift, shift, val) 

Also referenced here espressif/esp-idf#11875

PlatformIO Support

hi
i had an issue using your library
i copied all .h files from "include" folder and .cpp files from "src" folder and put them in together in my project
when i hit compile i get errors

In file included from src\include\hulp.cpp:1:
src\include\hulp.h:9:10: fatal error: hal/gpio_types.h: No such file or directory
#include "hal/gpio_types.h"
^~~~~~~~~~~~~~~~~~
compilation terminated.
In file included from src\include\hulp_debug.h:4,
from src\include\hulp_debug.cpp:1:
src\include\hulp.h:9:10: fatal error: hal/gpio_types.h: No such file or directory
#include "hal/gpio_types.h"
^~~~~~~~~~~~~~~~~~
compilation terminated.
In file included from src\include\hulp_touch.cpp:1:
src\include\hulp_touch.h:7:10: fatal error: soc/touch_sensor_channel.h: No such file or directory
#include "soc/touch_sensor_channel.h"
^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.

i'm using platformio
[env:esp32doit-devkit-v1]
platform = espressif32
board = esp32doit-devkit-v1
framework = arduino

Arduino ide8.16 compilation error on Mac

Hi, hope you can help. I am getting the following compilation error. Is it simply version incompatibility or is there something I can do to fix it?

In file included from /Users/charlesburgess/Documents/Arduino/libraries/HULP/src/hulp.h:8:0,
from /Users/charlesburgess/Documents/Arduino/Tests/ulp_examples/hulp_pulse_count/hulp_pulse_count.ino:1:
/Users/charlesburgess/Documents/Arduino/libraries/HULP/src/hulp_compat.h:8:6: error: #error "Unsupported IDF version"
#error "Unsupported IDF version"
^
/Users/charlesburgess/Documents/Arduino/libraries/HULP/src/hulp_compat.h:12:27: fatal error: esp32/clk.h: No such file or directory
compilation terminated.
exit status 1
Error compiling for board ESP32 Dev Module.

Pulse counter

Hi @boarchuz
I'm trying to build a pulse counter. I tried using your ADC exemple but it is not working.
I have a switch with a pulldown resistor on pin 34
Here is my code
`#include "hulp_arduino.h"
#define PIN_PLUV GPIO_NUM_34
#define PIN_PLUV_WAKE_THRESHOLD (4090)
#define ULP_WAKEUP_INTERVAL_MS (20) //Debouncers timer
int TIME_TO_SLEEP = 60; //Time EPS32 will go to sleep in seconds

RTC_DATA_ATTR ulp_var_t counter_pluv;

void ulp_init(){
enum {
LBL_PIN_PLUV_HIGH, //This labels are use as if function
LBL_HALT,
};
const ulp_insn_t program[] = {
//ULP
I_MOVI(R1,0), //Copy an immediate value into register: R1
I_ANALOG_READ(R1, PIN_PLUV),
I_SUBI(R0, R1, PIN_PLUV_WAKE_THRESHOLD), //Subtract register and an immediate value //// Subtract the threshold. If it overflows, the value must be < threshold so process the event.
M_BXF(LBL_PIN_PLUV_HIGH),
M_BX(LBL_HALT),
//
M_LABEL(LBL_PIN_PLUV_HIGH),
//increment counter if PIN_PLUV == HIGH
I_GET(R0,R1, counter_pluv), //Load value from RTC memory into reg_dest register.
I_ADDI(R0,R0,1), //R0++
I_PUT(R0,R1, counter_pluv), //Load value from reg_dest register to RTC memory.
M_WAKE_WHEN_READY(),
//
M_LABEL(LBL_HALT),
I_HALT(), //Halt the coprocessor but keeps ULP timer active
};
ESP_ERROR_CHECK(hulp_configure_analog_pin(PIN_PLUV));
ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 1000UL * ULP_WAKEUP_INTERVAL_MS, 0));
ESP_ERROR_CHECK(hulp_ulp_run(0));

}

void sleep (){
Serial.println("Going to sleep for "+ String(TIME_TO_SLEEP) + " seconds");
esp_sleep_enable_timer_wakeup(TIME_TO_SLEEP * 1000000);
delay(100);
Serial.flush();
esp_sleep_enable_ulp_wakeup();
esp_deep_sleep_start();
}
void setup() {
// put your setup code here, to run once:
Serial.begin(115200);
Serial.println("Program is starting");
ulp_init;

Serial.println("Pluv counter = " + String(counter_pluv.val));
sleep();

}

void loop() {
}`

Can you help on this ?

Thank you for your help

Is HULP compatible with ESP32-S3?

Hello, I'm trying to run the Arduino ADC basic.ino example on an ESP32S3, and getting a bunch of compile errors. Is HULP able to run on an ESP32-S3, or does the RISC-V architecture make it incompatible? Thanks!

undefined reference error in example code for simple debugging

Hi @boarchuz,
compiling named code returns with an error:

main.cpp:51: undefined reference to `hulp_debug_bp_init(hulp_debug_bp_config_t const*, hulp_debug_bp_state_t**)'

as the definition in "hulp_debug.h" asks for two arguments:

esp_err_t hulp_debug_bp_init(const hulp_debug_bp_config_t* config, hulp_debug_bp_handle_t* handle = nullptr);

I am not comfortable with cpp-coding, so I kindly ask for confirmation and your help.

touch, ULP FSM instructions, without macros

Here's a simple touch read in assembly, without using the macros. Parts of HULP have been included. the files in this arduino project. Files: esp32_ulp_touch: esp32_ulp_touch.ino, stuff.h, touch.h, touch.c, ulp.s, ulp_main.h.

esp32_ulp_touch.ino:

#include "driver/rtc_io.h"
#include "esp32/ulp.h"
// include ulp header you will create
#include "ulp_main.h"
// include ulptool binary load function
#include "ulptool.h"

#include "driver/gpio.h"
#include "soc/rtc.h"
#include "esp_sleep.h"
#include "touch.h"

#define uS_TO_S_FACTOR 1000000ULL  /* Conversion factor for micro seconds to seconds */
#define TIME_TO_SLEEP  5        /* Time ESP32 will go to sleep (in seconds) */


// this MUST be the same as PIN_TOUCH in the ulp.S file.
//#define PIN_TOUCH GPIO_NUM_32
#define PIN_TOUCH GPIO_NUM_4

#define ULP_TOUCH_INTERVAL_MS 2000

/**
 * ULP sleep duration in ms.
 */
#define ULP_SLEEP_PERIOD 1000

enum {
    LBL_TOUCH_INTERVAL,
    LBL_HALT,
};


// Unlike the esp-idf always use these binary blob names
extern const uint8_t ulp_main_bin_start[] asm("_binary_ulp_main_bin_start");
extern const uint8_t ulp_main_bin_end[]   asm("_binary_ulp_main_bin_end");

// do some blinking too.
gpio_num_t ulp_blink_pin = GPIO_NUM_25; // this is for the Heltec Wireless Stick Lite

void initBlinkPin() {
  Serial.println("initBlinkPin");
  rtc_gpio_init(ulp_blink_pin); 

  //rtc_gpio_pulldown_dis(ulp_blink_pin); // disable VCOM pulldown (saves 80µA). what's this about?
  rtc_gpio_set_direction(ulp_blink_pin, RTC_GPIO_MODE_OUTPUT_ONLY);
	
	// blink once:
  rtc_gpio_set_level(ulp_blink_pin, 0);
  delay(500);
  rtc_gpio_set_level(ulp_blink_pin, 1);
  delay(500);
  rtc_gpio_set_level(ulp_blink_pin, 0);
  }


static void init_run_ulp(uint32_t usec);

void setup() {
  Serial.begin(115200);
  delay(200);
  // put your setup code here, to run once:
  
	initBlinkPin();
	init_run_ulp(ULP_TOUCH_INTERVAL_MS * 1000); // 1000 msec
    
  const hulp_touch_controller_config_t controller_config = HULP_TOUCH_CONTROLLER_CONFIG_DEFAULT();
  ESP_ERROR_CHECK(hulp_configure_touch_controller(&controller_config));

  const hulp_touch_pin_config_t pin_config = HULP_TOUCH_PIN_CONFIG_DEFAULT();
  ESP_ERROR_CHECK(hulp_configure_touch_pin(PIN_TOUCH, &pin_config));
}

void loop() {
  // put your main code here, to run repeatedly:
  delay(ULP_TOUCH_INTERVAL_MS);
  Serial.printf("touch val: %u ", ulp_touch_val & 0xFFFF);
}

/*
 * usec: sleep period.
 */
static void init_run_ulp(uint32_t usec) {
    // initialize ulp variable
    ulp_set_wakeup_period(0, usec);
    esp_err_t err = ulptool_load_binary(0, ulp_main_bin_start, (ulp_main_bin_end - ulp_main_bin_start) / sizeof(uint32_t));
    // ulp coprocessor will run on its own now
    ulp_count = 0;
    err = ulp_run((&ulp_entry - RTC_SLOW_MEM) / sizeof(uint32_t));
    if (err) Serial.println("Error Starting ULP Coprocessor");
}

stuff.h:

// from https://github.com/espressif/esp-idf/blob/166c30e7b2ed1dcaae56179329540a862915208a/components/ulp/ulp_riscv/include/ulp_riscv/ulp_riscv_gpio.h

#ifndef ONCE_ONLY
#define ONCE_ONLY

typedef enum {
    RTCIO_MODE_OUTPUT = 0,
    RTCIO_MODE_OUTPUT_OD = 1,
} rtc_io_out_mode_t;



#define SOC_TOUCH_SENSOR_NUM                (15)  
// from https://github.com/espressif/esp-idf/blob/1cb31e50943bb757966ca91ed7f4852692a5b0ed/components/soc/esp32s3/include/soc/touch_sensor_caps.h

// from https://github.com/espressif/esp-idf/blob/master/components/soc/esp32/touch_sensor_periph.c
/* Store IO number corresponding to the Touch Sensor channel number. */
const int touch_sensor_channel_io_map[SOC_TOUCH_SENSOR_NUM] = {
    TOUCH_PAD_NUM0_GPIO_NUM,
    TOUCH_PAD_NUM1_GPIO_NUM,
    TOUCH_PAD_NUM2_GPIO_NUM,
    TOUCH_PAD_NUM3_GPIO_NUM,
    TOUCH_PAD_NUM4_GPIO_NUM,
    TOUCH_PAD_NUM5_GPIO_NUM,
    TOUCH_PAD_NUM6_GPIO_NUM,
    TOUCH_PAD_NUM7_GPIO_NUM,
    TOUCH_PAD_NUM8_GPIO_NUM,
    TOUCH_PAD_NUM9_GPIO_NUM
};



/********************************/
#define TOUCH_PAD_BIT_MASK_ALL              ((1<<SOC_TOUCH_SENSOR_NUM)-1)
#define TOUCH_PAD_SLOPE_DEFAULT             (TOUCH_PAD_SLOPE_7)
#define TOUCH_PAD_TIE_OPT_DEFAULT           (TOUCH_PAD_TIE_OPT_LOW)
// #define TOUCH_PAD_BIT_MASK_MAX              (TOUCH_PAD_BIT_MASK_ALL)
#define TOUCH_PAD_HIGH_VOLTAGE_THRESHOLD    (TOUCH_HVOLT_2V7)
#define TOUCH_PAD_LOW_VOLTAGE_THRESHOLD     (TOUCH_LVOLT_0V5)
#define TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD   (TOUCH_HVOLT_ATTEN_0V5)
#define TOUCH_PAD_IDLE_CH_CONNECT_DEFAULT   (TOUCH_PAD_CONN_GND)
#define TOUCH_PAD_THRESHOLD_MAX             (SOC_TOUCH_PAD_THRESHOLD_MAX) /*!<If set touch threshold max value, The touch sensor can't be in touched status */

#endif // ONCE_ONLY

touch.h:

#ifndef HULP_TOUCH_H
#define HULP_TOUCH_H

#include "driver/gpio.h"
#include "driver/touch_pad.h"
#include "touch_sensor_types.h"
#include "stuff.h"

#ifdef __cplusplus
extern "C" {
#endif

#define SWAPPED_TOUCH_INDEX(x) ((x) == TOUCH_PAD_NUM9 ? TOUCH_PAD_NUM8 : ((x) == TOUCH_PAD_NUM8 ? TOUCH_PAD_NUM9 : (x)))

typedef struct {
    uint16_t fastclk_meas_cycles;
    touch_high_volt_t high_voltage;
    touch_low_volt_t low_voltage;
    touch_volt_atten_t attenuation;
} hulp_touch_controller_config_t;

#define HULP_TOUCH_CONTROLLER_CONFIG_DEFAULT() { \
    .fastclk_meas_cycles = TOUCH_PAD_MEASURE_CYCLE_DEFAULT, \
    .high_voltage = TOUCH_HVOLT_2V4, \
    .low_voltage = TOUCH_LVOLT_0V8, \
    .attenuation = TOUCH_HVOLT_ATTEN_1V5, \
}

/**
 * Prepare touch controller for ULP control.
 * Do this once, then configure each pin using hulp_configure_touch_pin.
 * fastclk_meas_cycles: measurement time in fastclk (8MHz) cycles. (65535 = 8.19ms)
 * Shorter = lower power consumption; Longer = higher counts (better possible signal/noise filtering)
 */
esp_err_t hulp_configure_touch_controller(const hulp_touch_controller_config_t *config);

typedef struct {
    touch_cnt_slope_t slope;
    touch_tie_opt_t tie_opt;
} hulp_touch_pin_config_t;

#define HULP_TOUCH_PIN_CONFIG_DEFAULT() { \
    .slope = TOUCH_PAD_SLOPE_DEFAULT, \
    .tie_opt = TOUCH_PAD_TIE_OPT_DEFAULT, \
}

/**
 * Initialise and configure a pin for touch function.
 */
esp_err_t hulp_configure_touch_pin(gpio_num_t touch_gpio, const hulp_touch_pin_config_t *config);


#define I_TOUCH_GET_PAD_THRESHOLD(touch_num) \
    I_RD_REG((SENS_SAR_TOUCH_THRES1_REG + (4 * ((uint8_t)SWAPPED_TOUCH_INDEX(touch_num)/2))), (uint8_t)(SWAPPED_TOUCH_INDEX(touch_num)%2 ? 0 : 16), (uint8_t)(SWAPPED_TOUCH_INDEX(touch_num)%2 ? 15 : 31))

#define I_TOUCH_GET_GPIO_THRESHOLD(gpio_num) \
    I_TOUCH_GET_PAD_THRESHOLD(hulp_touch_get_pad_num(gpio_num))

#define I_TOUCH_GET_PAD_VALUE(touch_num) \
    I_RD_REG((SENS_SAR_TOUCH_OUT1_REG + (4 * ((uint8_t)SWAPPED_TOUCH_INDEX(touch_num)/2))), (uint8_t)((SWAPPED_TOUCH_INDEX(touch_num)%2) ? 0 : 16), (uint8_t)((SWAPPED_TOUCH_INDEX(touch_num)%2) ? 15 : 31))

#define I_TOUCH_GET_GPIO_VALUE(gpio_num) \
    I_TOUCH_GET_PAD_VALUE(hulp_touch_get_pad_num(gpio_num))

#define I_TOUCH_GET_DONE_BIT() \
    I_RD_REG_BIT(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_DONE_S)

#define M_TOUCH_WAIT_DONE() \
    I_TOUCH_GET_DONE_BIT(), \
    I_BL(-1,1)

#define M_TOUCH_BEGIN() \
    I_WR_REG_BIT(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_S, 0), \
    I_WR_REG_BIT(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_S, 1)

//Junk:
/**
 * Internal. Do not use directly.
 */
int hulp_touch_get_pad_num(gpio_num_t pin);

#ifdef __cplusplus
}
#endif

#endif // HULP_TOUCH_H

touch.c:

#include "esp_log.h"
#include "driver/touch_pad.h"
#include "stuff.h"
#include "touch.h"




static const char* TAG = "HULP-TCH";

int hulp_touch_get_pad_num(gpio_num_t pin)
{
    for(int i = 0; i < SOC_TOUCH_SENSOR_NUM; ++i)
    {
        if(touch_sensor_channel_io_map[i] == pin) return i;
    }
    ESP_LOGW(TAG, "no touch pad for gpio %d", pin);
    return -1;
}

esp_err_t hulp_configure_touch_controller(const hulp_touch_controller_config_t *config)
{
    if(!config)
    {
        return ESP_ERR_INVALID_ARG;
    }

    esp_err_t err;
    if( 
        ESP_OK != (err = touch_pad_init()) ||
        ESP_OK != (err = touch_pad_set_fsm_mode(TOUCH_FSM_MODE_SW)) ||
        ESP_OK != (err = touch_pad_set_voltage(config->high_voltage, config->low_voltage, config->attenuation)) ||
        //sw control so sleep_cycle is irrelevant here; set to default
        ESP_OK != (err = touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, config->fastclk_meas_cycles))
    )
    {
        ESP_LOGE(TAG, "[%s] err (0x%x)", __func__, err);
        return err;
    }
    return ESP_OK;
}

esp_err_t hulp_configure_touch_pin(gpio_num_t touch_gpio, const hulp_touch_pin_config_t *config)
{
    if(!config)
    {
        return ESP_ERR_INVALID_ARG;
    }

    int touch_pad_num = hulp_touch_get_pad_num(touch_gpio);
    if(touch_pad_num < 0)
    {
        ESP_LOGE(TAG, "invalid touch pin (%d)", touch_gpio);
        return ESP_ERR_INVALID_ARG;
    }

    esp_err_t err;
    if(
        ESP_OK != (err = touch_pad_io_init(touch_pad_num)) ||
        ESP_OK != (err = touch_pad_set_cnt_mode(touch_pad_num, config->slope, config->tie_opt)) ||
        ESP_OK != (err = touch_pad_set_group_mask(0, 0, 1 << touch_pad_num))
    )
    {
        ESP_LOGE(TAG, "[%s] err (0x%x)", __func__, err);
        return err;
    }
    return ESP_OK;
}

ulp.s:

#include "soc/rtc_cntl_reg.h"
#include "soc/soc_ulp.h"
#include "soc/rtc_io_reg.h"
#include "soc/sens_reg.h"


// touch read. also blink the LED (define pin based on your microcontroller)
    .bss

// 3.44ms seems to be the time taken for a touch read. 
// "time_reg_e" - "time_reg" is about 572, and 1 sec is about 166152 RTC clock cycles, so 572/166152 = 3.44ms.


// touch read start time:
    .global time_reg_1
time_reg_1:
    .long 0

    .global time_reg_2
time_reg_2:
    .long 0

    .global time_reg_3
time_reg_3:
    .long 0

// touch read end time:
    .global time_reg_e1
time_reg_e1:
    .long 0

    .global time_reg_e2
time_reg_e2:
    .long 0

    .global time_reg_e3
time_reg_e3:
    .long 0

    .data

     .global touch_val
touch_val:
    .long 0

    .text
  .global entry
entry:
    .global loop1

loop1:



    
// turn LED on
    // WRITE_RTC_REG(RTC_GPIO_OUT_REG,RTC_GPIO_OUT_DATA_S+12,1,1)
    WRITE_RTC_REG(RTC_GPIO_OUT_REG,RTC_GPIO_OUT_DATA_S+6,1,1)


// wait a bit, loop a few times.
    MOVE       R0, 0x00          //R0 = 0x00
loop_blink:

    WAIT 65535
    Add R0, R0, 0x01    //R0++
    jumpr jump_out, 17, GT  // if count >17, jump out
    jump loop_blink // otherwise keep looping
 jump_out:
 

// turn LED off
    // WRITE_RTC_REG(RTC_GPIO_OUT_REG,RTC_GPIO_OUT_DATA_S+12,1,0)
    WRITE_RTC_REG(RTC_GPIO_OUT_REG,RTC_GPIO_OUT_DATA_S+6,1,0)


// wait a bit, loop a few times.
    MOVE       R0, 0x00          //R0 = 0x00
loop_blink2:
    WAIT 65535
    Add R0, R0, 0x01    //R0++
    jumpr jump_out2, 17, GT  // if count >17, jump out
    jump loop_blink2 // otherwise keep looping
 jump_out2:


     // now let's start the touch read code:

    

.set SIZEOF_UINT32T, 4  // num bytes in a 32-bit word
.set PIN_TOUCH, 0 // GPIO 4


/**
 * Touch pad control and status
 * See TRM pg 649, Register 30.18: SENS_SAR_TOUCH_CTRL2_REG (0x0084)
 */
#define SENS_SAR_TOUCH_CTRL2_REG          (DR_REG_SENS_BASE + 0x0084)  // from sens_reg.h


// store system time, just before starting a touch read.
read_time1:
    /* Trigger update of register */
    WRITE_RTC_REG(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_UPDATE_S, 1, 1)
    JUMP check_time_valid1  // probably don't need this instruction

check_time_valid1:
    /* Check if RTC_CNTL_TIME_VALID bit is 1, otherwise repeat */
    READ_RTC_REG(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_VALID_S, 1)
    AND R0, R0, 1
    JUMP check_time_valid1, EQ
    
    /* Read timer registers */
    READ_RTC_REG(RTC_CNTL_TIME0_REG, 0, 16)
    MOVE R2, time_reg_1
    ST R0, R2, 0

    REG_RD 0x3FF48010, 31, 16
    MOVE R2, time_reg_2
    ST R0, R2, 0

    REG_RD 0x3FF48014, 15, 0
    MOVE R2, time_reg_3
    ST R0, R2, 0


/**
 * 
 * ----------------- 1. Begin a new touch read ----------------- 
 * 
 */

/**
 * Write the register, once with 0, once with 1, to start the sensing.
 *
 */

WRITE_RTC_REG(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_S, 1, 0)
WRITE_RTC_REG(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_START_EN_S, 1, 1)

/**
 * 
 * ----------------- 2. Wait for it to complete -----------------
 * Read SENS_TOUCH_MEAS_DONE until it is non-zero (keep looping), meaning that 
 * the reading is done. (see TRM)
 * 
 * see soc\sens_reg.h. also esp32_technical_reference_manual_en.pdf p. 649
 * Set to 1 by FSM, indicating that touch measurement is done. (RO, Read Only)
 * 
 */

MOVE R1, 0  // to keep count

read_again:    // label
/**
 * read peripheral register into R0. it'll be bit #10, so 2^10 = 1024 if it is non-zero.
 */

/* Read 1-bit SENS_TOUCH_MEAS_DONE field of SENS_SAR_TOUCH_CTRL2_REG into R0 */
READ_RTC_FIELD(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_DONE)


// if R0 < 1, goto read_again. we only care if it is zero or not.
JUMPR read_again, 1, LT // appears the step is automatically calculated by the assembler. For example, jumpr didInit,1,ge, from i2c.s in ArduinoData\packages\esp32\tools\ulptool\src\ulp_examples\ulp_i2c_bitbang

/**
 * 
 * ----------------- 3. Get the value for selected pin -----------------
 * Now that we know that the scanning/measuring is over, get the result. 
 * As we're using only a single pin and don't need generic handling,
 * we can skip the swap check for pins 8 & 9.
 */
 

/* Read 1-bit SENS_TOUCH_MEAS_OUT0 field of SENS_SAR_TOUCH_OUT1_REG into R0 */
READ_RTC_FIELD(SENS_SAR_TOUCH_OUT1_REG, SENS_TOUCH_MEAS_OUT0)

/**
 * ----------------- 4. Update the variable with the new value -----------------
 * R0 has the the value. set:
 * touch_val = R0
 */

move    r3, touch_val   // R3 = address_of(touch_val) / 4    
                        // ld      r0, r3, 0   // LD Rdst, Rsrc, offset. // R0 = MEM[R3+0x00]
                        // add     r0, r0, 1   // ADD Rdst, Rsrc1, imm. r0 = r0 + 1
st      r0, r3, 0   // ST Rsrc, Rdst, offset. MEM[R3+0x00] = R0


// store system time after touch read
read_time2:
    /* Trigger update of register */
    WRITE_RTC_REG(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_UPDATE_S, 1, 1)
    JUMP check_time_valid2  // probably don't need this instruction
    

check_time_valid2:
    /* Check if RTC_CNTL_TIME_VALID bit is 1, otherwise repeat */
    READ_RTC_REG(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_VALID_S, 1)
    AND R0, R0, 1
    JUMP check_time_valid2, EQ
    
    /* Read timer registers */
    READ_RTC_REG(RTC_CNTL_TIME0_REG, 0, 16)
    MOVE R2, time_reg_e1
    ST R0, R2, 0

    REG_RD 0x3FF48010, 31, 16
    MOVE R2, time_reg_e2
    ST R0, R2, 0

    REG_RD 0x3FF48014, 15, 0
    MOVE R2, time_reg_e3
    ST R0, R2, 0



HALT

ulp_main.h:

/*
    Put your ULP globals here you want visibility
    for your sketch. Add "ulp_" to the beginning
    of the variable name and must be size 'uint32_t'
*/
#include "Arduino.h"

extern uint32_t ulp_entry;

extern uint32_t ulp_touch_val;


Example for HX711

Hello!
Thank you for this great resource!

I have been in search of some code examples that would help me wake the ESP32 when the ULP notices a difference in weight from a HX711 sensor.

I notice you have in this repo a threshold example for a hall effect sensor. Would I be correct in thinking that this would be a very similar approach for the HX711?

The code is a little over my head but I will try my best to contribute an example for the HX711 if I can figure it out.

Thanks again!

How can I make this work with Arduino?

Hello,

I really want to use this library in my project. However, our application is already pretty far in using the Arduino framework, so if there's a way of installing this in Platform IO, that'd be appreciated.

I tried to download the source files, but I get all of these errors having to do with include paths and esp-idf versions and so on.

I just want to make sure I'm not completely wasting my time.

Thanks for the help!

Measuring pulse length in milliseconds

I'm stuck on what is the best way to go about measuring the time between two interrupts (each on the rising and falling edges of a pulse of <500ms) with millisecond accuracy? Handing the interrupts themselves is no issue, just the timing between the two.

I've tried a counter using 'M_IF_MS_ELAPSED()' and just reading clock ticks with 'I_RD_TICKS()' with but neither producing needed results.

Any help is greatly appreciated, I'm definitely out of my depth there!

Thanks!

CURRENT CODE:

#include "hulp_arduino.h"

#define RAIN_PIN GPIO_NUM_33
#define WIND_PIN GPIO_NUM_32
RTC_DATA_ATTR ulp_var_t rain;
RTC_DATA_ATTR ulp_var_t wind; 
RTC_DATA_ATTR ulp_var_t gust;

void setup() {
  Serial.begin(115200);
   ulp_init();
}

void loop() {
  Serial.print("Rain: ");
  Serial.println(rain.val);
  Serial.print("Wind: ");
  Serial.println(wind.val);
  Serial.println();
  rain.val = 0;
  wind.val = 0;

  //ESP enter deep sleep for 1 minute
}


void ulp_init() {
  enum {
    RAIN_PIN_TRIGGERED,
    WIND_PIN_TRIGGERED,
    HANDLE_RAIN,
    HANDLE_WIND,
    LBL_HALT,
  };
  const ulp_insn_t program[] = {
    M_UPDATE_TICKS(),

    M_LABEL(HANDLE_RAIN),
      I_GPIO_INT_RD(RAIN_PIN), 
      M_BGE(RAIN_PIN_TRIGGERED, 1), 
      M_BX(HANDLE_WIND), 
    M_LABEL(RAIN_PIN_TRIGGERED), 
      I_GPIO_INT_CLR(RAIN_PIN), 
      I_MOVI(R1, 0), 
      I_GET(R0, R1, rain), 
      I_ADDI(R0, R0, 1), 
      I_PUT(R0, R1, rain),
      M_BX(HANDLE_WIND),

    M_LABEL(HANDLE_WIND),
        I_GPIO_INT_RD(WIND_PIN), 
        M_BGE(WIND_PIN_TRIGGERED, 1), 
        M_BX(LBL_HALT),
    M_LABEL(WIND_PIN_TRIGGERED), 
        I_GPIO_INT_CLR(WIND_PIN), 
        I_MOVI(R1, 0), 
        I_GET(R0, R1, wind), 
        I_ADDI(R0, R0, 1), 
        I_PUT(R0, R1, wind), 
        M_BX(LBL_HALT),   
        //INSERT WIND TIMING CODE HERE

    M_LABEL(LBL_HALT),
      I_HALT(),  
  };

  //Pin configuration
  hulp_peripherals_on();
  ESP_ERROR_CHECK(hulp_configure_pin(RAIN_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_PULLDOWN_ONLY, 0));
  ESP_ERROR_CHECK(hulp_configure_pin_int(RAIN_PIN, GPIO_INTR_ANYEDGE));
  ESP_ERROR_CHECK(hulp_configure_pin(WIND_PIN, RTC_GPIO_MODE_INPUT_ONLY, GPIO_PULLDOWN_ONLY, 0));
  ESP_ERROR_CHECK(hulp_configure_pin_int(WIND_PIN, GPIO_INTR_ANYEDGE));
  ESP_ERROR_CHECK(hulp_configure_pin(POWER_PIN, RTC_GPIO_MODE_OUTPUT_ONLY, GPIO_FLOATING, 0));
  ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), 1 * 10 * 1000, 0)); //10 mS sleep time
  ESP_ERROR_CHECK(hulp_ulp_run(0));
}

I2C bitbanging write 16bit

Some sensors like the ADS-111x DO require 16-bit readouts.
Could you please add a macro for 16 bit write?

Possible confrontation with some libraries

This is not an issue but it could indicate that there is a problem. Here's what it's all about:
I have completed one small program that finds the min and max sine waves sampled by the ADC converter on the input GPIO34. That program is run by a ULP co-processor and everything is fine. However when I add that program to the existing ESP32 program, for WiFi connection and tracking results, I get completely irrelevant values ​​from ULP. Of course, I first suspected WiFi, and then added the ULP program to one of the examples for the ESP32 wifi server. Except that you have to add a small 330pF capacitor between the ADC inputPIN and ground, everything else works great.
I use several libraries to run the main program and I can't guess which one has an impact on the ULP program. To analyze this, I could somehow get data on how the ULP program and the variables arranged in memory. Is it possible to extract this from the compilation files?

regards, freetoair

What are plans for documentation?

@boarchuz Firstly, thank you so much for creating this library - it looks very promising!

What are your plans for documentation? I see some nice function descriptions in the header files. I'm curious if you're planning to use a system like doxygen or spinx to autogenerate documentation.

Cheers!

HULP I2C Hardware Read Wemos Ambient Light sensor BH1750 question

Hi @boarchuz,
Thank you very much for your incredible library that makes it possible for me to approach the ULP programming.
I'm working with ESP32 (ESP32-DevKitM-1 with an ESP32-MINI-1 MCU) in Arduino IDE configured as generic ESP32 Dev Module.
I'm trying the I2C Hardware Read example included in your library, slightly modified for use with the Wemos ambient light sensor BH1750 (I2C address is 0x23), but I can't get it to work right. I don't know about subaddress.

This is the code:


#include <Arduino.h>
#include <hulp_arduino.h>

#define ULP_REPEAT_INTERVAL_MS 1000
#define SCL_PIN GPIO_NUM_4            // D1
#define SDA_PIN GPIO_NUM_15           // D2
#define LIGHT_SENSOR_I2C_ADDR 35      // 0x23
#define LIGHT_SENSOR_I2C_SUBADDR 0    // 0x00

RTC_DATA_ATTR ulp_var_t ulp_data;

void init_ulp()
{
  const ulp_insn_t program[] = {
    I_MOVI(R2, 0),
    I_I2C_READ(0, LIGHT_SENSOR_I2C_SUBADDR),
    I_PUT(R0, R2, ulp_data),
    I_HALT(),
  };

  hulp_register_i2c_slave(0, LIGHT_SENSOR_I2C_ADDR);
  ESP_ERROR_CHECK(hulp_configure_i2c_pins(SCL_PIN, SDA_PIN, true, true));

  const hulp_i2c_controller_config_t config = HULP_I2C_CONTROLLER_CONFIG_DEFAULT();

  ESP_ERROR_CHECK(hulp_configure_i2c_controller(&config));
  ESP_ERROR_CHECK(hulp_ulp_load(program, sizeof(program), ULP_REPEAT_INTERVAL_MS * 1000, 0));
  ESP_ERROR_CHECK(hulp_ulp_run(0));
}

void setup()
{
  Serial.begin(115200);
  init_ulp();
}

void loop()
{
  Serial.print(F("Light sensor I2C data: "));
  Serial.println(ulp_data.val);
  delay(1000);
}

And this is what I get:

10:35:24.270 -> ets Jul 29 2019 12:21:46
10:35:24.270 ->
10:35:24.270 -> rst:0x1 (POWERON_RESET),boot:0x17 (SPI_FAST_FLASH_BOOT)
10:35:24.270 -> configsip: 188777542, SPIWP:0xee
10:35:24.270 -> clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
10:35:24.270 -> mode:DIO, clock div:1
10:35:24.270 -> load:0x3fff0030,len:1344
10:35:24.270 -> load:0x40078000,len:13516
10:35:24.312 -> load:0x40080400,len:3604
10:35:24.312 -> entry 0x400805f0
10:35:24.394 -> Light sensor I2C data: 0
10:35:25.409 -> Light sensor I2C data: 1
10:35:26.385 -> Light sensor I2C data: 1 (repeated indefinitely)

I've also tried with VSCode and PlatformIO in Arduino framework; same results.
On the other hand, the module works without any problem outside of the ULP/HULP programming, that is, with the main processor and the Wire.h and BH1750.h libraries.

Could you please help me by telling me what I am doing wrong?

ADC example, comparing if value is wihin a range, rather than just under a threshold

So, in the ADC example, which by the way is very convenient and covers many cases, i try to compare the PiN3 against a range, rather than if it is below a certain threashold.

Because, when used with ADKEYS typically several keys are on the same GPIO and i want to wake up the system only if a certain key is pressed.

What is the best way to do this? I see where you compare wether it is below the threashold, but i am not sure how to compare if it is below the threshold and over another threshold.

            I_ANALOG_READ(R1, PIN_ADC_PIN3),
            I_PUT(R1, R3, ulp_vars.pin3.debug),
            // Skip if the trigger isn't 'armed'. SoC enables this before going to sleep (see below).
            I_GET(R0, R3, ulp_vars.pin3.armed),
            M_BL(LBL_HALT, 1),
            // Subtract the threshold. If it overflows, the value must be < threshold so process the event.
            I_SUBI(R0, R1, PIN3_WAKE_THRESHOLD),
            M_BXF(LBL_PIN3_WAKEUP_TRIGGERED),
            M_BX(LBL_HALT),
            M_LABEL(LBL_PIN3_WAKEUP_TRIGGERED),

I think updating the example with that function would be useful to others working with ADKEYs.

Thanks.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.