Skip to content

Commit

Permalink
faster GPIO using direct IO registers for ESP8266
Browse files Browse the repository at this point in the history
  • Loading branch information
Paciente8159 committed Jan 14, 2025
1 parent 1ed8542 commit 6aaddb8
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 9 deletions.
4 changes: 0 additions & 4 deletions uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,6 @@ extern "C"
bool mcu_custom_grbl_cmd(void *args)
{
grbl_cmd_args_t *cmd_params = (grbl_cmd_args_t *)args;
uint8_t str[64];
char arg[ARG_MAX_LEN];
uint8_t has_arg = (cmd_params->next_char == '=');
memset(arg, 0, sizeof(arg));
Expand Down Expand Up @@ -310,7 +309,6 @@ extern "C"
#ifdef ENABLE_WIFI
static uint32_t next_info = 30000;
static bool connected = false;
uint8_t str[64];

if (!wifi_settings.wifi_on)
{
Expand Down Expand Up @@ -730,8 +728,6 @@ extern "C"

if (wifi_settings.wifi_on)
{
uint8_t str[64];

switch (wifi_settings.wifi_mode)
{
case 1:
Expand Down
10 changes: 5 additions & 5 deletions uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h
Original file line number Diff line number Diff line change
Expand Up @@ -1233,11 +1233,11 @@ extern "C"
#define mcu_config_pullup(X) pinMode(__indirect__(X, BIT), INPUT_PULLUP)
#define mcu_config_input_isr(X) attachInterrupt(digitalPinToInterrupt(__indirect__(X, BIT)), __indirect__(X, ISRCALLBACK), CHANGE)

#define mcu_get_input(X) digitalRead(__indirect__(X, BIT))
#define mcu_get_output(X) digitalRead(__indirect__(X, BIT))
#define mcu_set_output(X) digitalWrite(__indirect__(X, BIT), 1)
#define mcu_clear_output(X) digitalWrite(__indirect__(X, BIT), 0)
#define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT)))
#define mcu_get_input(X) ((__indirect__(X, BIT) != 16) ? GPIP(__indirect__(X, BIT)) : (GP16I & 0x01))
#define mcu_get_output(X) ((__indirect__(X, BIT) != 16) ? GPIP(__indirect__(X, BIT)) : (GP16I & 0x01))
#define mcu_set_output(X) ({if(__indirect__(X, BIT)!=16){GPOS=(1<<__indirect__(X, BIT));}else{GP16O |= 1;} })
#define mcu_clear_output(X) ({if(__indirect__(X, BIT)!=16){GPOC=(1<<__indirect__(X, BIT));}else{GP16O &= ~1;} })
#define mcu_toggle_output(X) ((!!mcu_get_output(X)) ? mcu_clear_output(X) : mcu_set_output(X))

#define mcu_get_analog(X) analogRead(__indirect__(X, BIT))

Expand Down

0 comments on commit 6aaddb8

Please sign in to comment.