From 9aa48141c39ed4645d258c7776893b06949685e0 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 5 Feb 2022 21:31:33 +0000 Subject: [PATCH 01/13] initial implementation for ESP8266 -initial implementation for ESP8266 based on Arduino 8266 core --- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 665 ++++++++++++++++++++ uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 700 +++++++++++++++++++++ 2 files changed, 1365 insertions(+) create mode 100644 uCNC/src/hal/mcus/esp8266/mcu_esp8266.c create mode 100644 uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c new file mode 100644 index 000000000..0562d126f --- /dev/null +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -0,0 +1,665 @@ +/* + Name: mcu_esp8266.c + Description: Implements the µCNC HAL for ESP8266. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 04-02-2022 + + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#include "../../../cnc.h" + +#if (MCU == MCU_ESP8266) + +#include "Arduino.h" +#include + +#include +#include +#include + +IRAM_ATTR void mcu_din_isr(void) +{ + io_inputs_isr(); +} + +IRAM_ATTR void mcu_probe_isr(void) +{ + io_probe_isr(); +} + +IRAM_ATTR void mcu_limits_isr(void) +{ + io_limits_isr(); +} + +IRAM_ATTR void mcu_controls_isr(void) +{ + io_controls_isr(); +} + +/** + * initializes the mcu + * this function needs to: + * - configure all IO pins (digital IO, PWM, Analog, etc...) + * - configure all interrupts + * - configure uart or usb + * - start the internal RTC + * */ +void mcu_init(void) +{ +#if STEP0 >= 0 + mcu_config_output(STEP0); +#endif +#if STEP1 >= 0 + mcu_config_output(STEP1); +#endif +#if STEP2 >= 0 + mcu_config_output(STEP2); +#endif +#if STEP3 >= 0 + mcu_config_output(STEP3); +#endif +#if STEP4 >= 0 + mcu_config_output(STEP4); +#endif +#if STEP5 >= 0 + mcu_config_output(STEP5); +#endif +#if STEP6 >= 0 + mcu_config_output(STEP6); +#endif +#if STEP7 >= 0 + mcu_config_output(STEP7); +#endif +#if DIR0 >= 0 + mcu_config_output(DIR0); +#endif +#if DIR1 >= 0 + mcu_config_output(DIR1); +#endif +#if DIR2 >= 0 + mcu_config_output(DIR2); +#endif +#if DIR3 >= 0 + mcu_config_output(DIR3); +#endif +#if DIR4 >= 0 + mcu_config_output(DIR4); +#endif +#if DIR5 >= 0 + mcu_config_output(DIR5); +#endif +#if STEP0_EN >= 0 + mcu_config_output(STEP0_EN); +#endif +#if STEP1_EN >= 0 + mcu_config_output(STEP1_EN); +#endif +#if STEP2_EN >= 0 + mcu_config_output(STEP2_EN); +#endif +#if STEP3_EN >= 0 + mcu_config_output(STEP3_EN); +#endif +#if STEP4_EN >= 0 + mcu_config_output(STEP4_EN); +#endif +#if STEP5_EN >= 0 + mcu_config_output(STEP5_EN); +#endif +#if PWM0 >= 0 + mcu_config_pwm(PWM0); +#endif +#if PWM1 >= 0 + mcu_config_pwm(PWM1); +#endif +#if PWM2 >= 0 + mcu_config_pwm(PWM2); +#endif +#if PWM3 >= 0 + mcu_config_pwm(PWM3); +#endif +#if PWM4 >= 0 + mcu_config_pwm(PWM4); +#endif +#if PWM5 >= 0 + mcu_config_pwm(PWM5); +#endif +#if PWM6 >= 0 + mcu_config_pwm(PWM6); +#endif +#if PWM7 >= 0 + mcu_config_pwm(PWM7); +#endif +#if PWM8 >= 0 + mcu_config_pwm(PWM8); +#endif +#if PWM9 >= 0 + mcu_config_pwm(PWM9); +#endif +#if PWM10 >= 0 + mcu_config_pwm(PWM10); +#endif +#if PWM11 >= 0 + mcu_config_pwm(PWM11); +#endif +#if PWM12 >= 0 + mcu_config_pwm(PWM12); +#endif +#if PWM13 >= 0 + mcu_config_pwm(PWM13); +#endif +#if PWM14 >= 0 + mcu_config_pwm(PWM14); +#endif +#if PWM15 >= 0 + mcu_config_pwm(PWM15); +#endif +#if DOUT0 >= 0 + mcu_config_output(DOUT0); +#endif +#if DOUT1 >= 0 + mcu_config_output(DOUT1); +#endif +#if DOUT2 >= 0 + mcu_config_output(DOUT2); +#endif +#if DOUT3 >= 0 + mcu_config_output(DOUT3); +#endif +#if DOUT4 >= 0 + mcu_config_output(DOUT4); +#endif +#if DOUT5 >= 0 + mcu_config_output(DOUT5); +#endif +#if DOUT6 >= 0 + mcu_config_output(DOUT6); +#endif +#if DOUT7 >= 0 + mcu_config_output(DOUT7); +#endif +#if DOUT8 >= 0 + mcu_config_output(DOUT8); +#endif +#if DOUT9 >= 0 + mcu_config_output(DOUT9); +#endif +#if DOUT10 >= 0 + mcu_config_output(DOUT10); +#endif +#if DOUT11 >= 0 + mcu_config_output(DOUT11); +#endif +#if DOUT12 >= 0 + mcu_config_output(DOUT12); +#endif +#if DOUT13 >= 0 + mcu_config_output(DOUT13); +#endif +#if DOUT14 >= 0 + mcu_config_output(DOUT14); +#endif +#if DOUT15 >= 0 + mcu_config_output(DOUT15); +#endif +#if LIMIT_X >= 0 + mcu_config_input(LIMIT_X); +#ifdef LIMIT_X_PULLUP + mcu_config_pullup(LIMIT_X); +#endif +#ifdef LIMIT_X_ISR + mcu_config_input_isr(LIMIT_X); +#endif +#endif +#if LIMIT_Y >= 0 + mcu_config_input(LIMIT_Y); +#ifdef LIMIT_Y_PULLUP + mcu_config_pullup(LIMIT_Y); +#endif +#ifdef LIMIT_Y_ISR + mcu_config_input_isr(LIMIT_Y); +#endif +#endif +#if LIMIT_Z >= 0 + mcu_config_input(LIMIT_Z); +#ifdef LIMIT_Z_PULLUP + mcu_config_pullup(LIMIT_Z); +#endif +#ifdef LIMIT_Z_ISR + mcu_config_input_isr(LIMIT_Z); +#endif +#endif +#if LIMIT_X2 >= 0 + mcu_config_input(LIMIT_X2); +#ifdef LIMIT_X2_PULLUP + mcu_config_pullup(LIMIT_X2); +#endif +#ifdef LIMIT_X2_ISR + mcu_config_input_isr(LIMIT_X2); +#endif +#endif +#if LIMIT_Y2 >= 0 + mcu_config_input(LIMIT_Y2); +#ifdef LIMIT_Y2_PULLUP + mcu_config_pullup(LIMIT_Y2); +#endif +#ifdef LIMIT_Y2_ISR + mcu_config_input_isr(LIMIT_Y2); +#endif +#endif +#if LIMIT_Z2 >= 0 + mcu_config_input(LIMIT_Z2); +#ifdef LIMIT_Z2_PULLUP + mcu_config_pullup(LIMIT_Z2); +#endif +#ifdef LIMIT_Z2_ISR + mcu_config_input_isr(LIMIT_Z2); +#endif +#endif +#if LIMIT_A >= 0 + mcu_config_input(LIMIT_A); +#ifdef LIMIT_A_PULLUP + mcu_config_pullup(LIMIT_A); +#endif +#ifdef LIMIT_A_ISR + mcu_config_input_isr(LIMIT_A); +#endif +#endif +#if LIMIT_B >= 0 + mcu_config_input(LIMIT_B); +#ifdef LIMIT_B_PULLUP + mcu_config_pullup(LIMIT_B); +#endif +#ifdef LIMIT_B_ISR + mcu_config_input_isr(LIMIT_B); +#endif +#endif +#if LIMIT_C >= 0 + mcu_config_input(LIMIT_C); +#ifdef LIMIT_C_PULLUP + mcu_config_pullup(LIMIT_C); +#endif +#ifdef LIMIT_C_ISR + mcu_config_input_isr(LIMIT_C); +#endif +#endif +#if PROBE >= 0 + mcu_config_input(PROBE); +#ifdef PROBE_PULLUP + mcu_config_pullup(PROBE); +#endif +#ifdef PROBE_ISR + mcu_config_input_isr(PROBE); +#endif +#endif +#if ESTOP >= 0 + mcu_config_input(ESTOP); +#ifdef ESTOP_PULLUP + mcu_config_pullup(ESTOP); +#endif +#ifdef ESTOP_ISR + mcu_config_input_isr(ESTOP); +#endif +#endif +#if SAFETY_DOOR >= 0 + mcu_config_input(SAFETY_DOOR); +#ifdef SAFETY_DOOR_PULLUP + mcu_config_pullup(SAFETY_DOOR); +#endif +#ifdef SAFETY_DOOR_ISR + mcu_config_input_isr(SAFETY_DOOR); +#endif +#endif +#if FHOLD >= 0 + mcu_config_input(FHOLD); +#ifdef FHOLD_PULLUP + mcu_config_pullup(FHOLD); +#endif +#ifdef FHOLD_ISR + mcu_config_input_isr(FHOLD); +#endif +#endif +#if CS_RES >= 0 + mcu_config_input(CS_RES); +#ifdef CS_RES_PULLUP + mcu_config_pullup(CS_RES); +#endif +#ifdef CS_RES_ISR + mcu_config_input_isr(CS_RES); +#endif +#endif +#if ANALOG0 >= 0 + mcu_config_input(ANALOG0); +#endif +#if ANALOG1 >= 0 + mcu_config_input(ANALOG1); +#endif +#if ANALOG2 >= 0 + mcu_config_input(ANALOG2); +#endif +#if ANALOG3 >= 0 + mcu_config_input(ANALOG3); +#endif +#if ANALOG4 >= 0 + mcu_config_input(ANALOG4); +#endif +#if ANALOG5 >= 0 + mcu_config_input(ANALOG5); +#endif +#if ANALOG6 >= 0 + mcu_config_input(ANALOG6); +#endif +#if ANALOG7 >= 0 + mcu_config_input(ANALOG7); +#endif +#if ANALOG8 >= 0 + mcu_config_input(ANALOG8); +#endif +#if ANALOG9 >= 0 + mcu_config_input(ANALOG9); +#endif +#if ANALOG10 >= 0 + mcu_config_input(ANALOG10); +#endif +#if ANALOG11 >= 0 + mcu_config_input(ANALOG11); +#endif +#if ANALOG12 >= 0 + mcu_config_input(ANALOG12); +#endif +#if ANALOG13 >= 0 + mcu_config_input(ANALOG13); +#endif +#if ANALOG14 >= 0 + mcu_config_input(ANALOG14); +#endif +#if ANALOG15 >= 0 + mcu_config_input(ANALOG15); +#endif +#if DIN0 >= 0 + mcu_config_input(DIN0); +#ifdef DIN0_PULLUP + mcu_config_pullup(DIN0); +#endif +#ifdef DIN0_ISR + mcu_config_input_isr(DIN0); +#endif +#endif +#if DIN1 >= 0 + mcu_config_input(DIN1); +#ifdef DIN1_PULLUP + mcu_config_pullup(DIN1); +#endif +#ifdef DIN1_ISR + mcu_config_input_isr(DIN1); +#endif +#endif +#if DIN2 >= 0 + mcu_config_input(DIN2); +#ifdef DIN2_PULLUP + mcu_config_pullup(DIN2); +#endif +#ifdef DIN2_ISR + mcu_config_input_isr(DIN2); +#endif +#endif +#if DIN3 >= 0 + mcu_config_input(DIN3); +#ifdef DIN3_PULLUP + mcu_config_pullup(DIN3); +#endif +#ifdef DIN3_ISR + mcu_config_input_isr(DIN3); +#endif +#endif +#if DIN4 >= 0 + mcu_config_input(DIN4); +#ifdef DIN4_PULLUP + mcu_config_pullup(DIN4); +#endif +#ifdef DIN4_ISR + mcu_config_input_isr(DIN4); +#endif +#endif +#if DIN5 >= 0 + mcu_config_input(DIN5); +#ifdef DIN5_PULLUP + mcu_config_pullup(DIN5); +#endif +#ifdef DIN5_ISR + mcu_config_input_isr(DIN5); +#endif +#endif +#if DIN6 >= 0 + mcu_config_input(DIN6); +#ifdef DIN6_PULLUP + mcu_config_pullup(DIN6); +#endif +#ifdef DIN6_ISR + mcu_config_input_isr(DIN6); +#endif +#endif +#if DIN7 >= 0 + mcu_config_input(DIN7); +#ifdef DIN7_PULLUP + mcu_config_pullup(DIN7); +#endif +#ifdef DIN7_ISR + mcu_config_input_isr(DIN7); +#endif +#endif +#if DIN8 >= 0 + mcu_config_input(DIN8); +#ifdef DIN8_PULLUP + mcu_config_pullup(DIN8); +#endif +#endif +#if DIN9 >= 0 + mcu_config_input(DIN9); +#ifdef DIN9_PULLUP + mcu_config_pullup(DIN9); +#endif +#endif +#if DIN10 >= 0 + mcu_config_input(DIN10); +#ifdef DIN10_PULLUP + mcu_config_pullup(DIN10); +#endif +#endif +#if DIN11 >= 0 + mcu_config_input(DIN11); +#ifdef DIN11_PULLUP + mcu_config_pullup(DIN11); +#endif +#endif +#if DIN12 >= 0 + mcu_config_input(DIN12); +#ifdef DIN12_PULLUP + mcu_config_pullup(DIN12); +#endif +#endif +#if DIN13 >= 0 + mcu_config_input(DIN13); +#ifdef DIN13_PULLUP + mcu_config_pullup(DIN13); +#endif +#endif +#if DIN14 >= 0 + mcu_config_input(DIN14); +#ifdef DIN14_PULLUP + mcu_config_pullup(DIN14); +#endif +#endif +#if DIN15 >= 0 + mcu_config_input(DIN15); +#ifdef DIN15_PULLUP + mcu_config_pullup(DIN15); +#endif +#endif +#if TX >= 0 + mcu_config_output(TX); +#endif +#if RX >= 0 + mcu_config_output(RX); +#endif +} + +/** + * enables the pin probe mcu isr on change + * can be defined either as a function or a macro call + * */ +#ifndef mcu_enable_probe_isr +void mcu_enable_probe_isr(void); +#endif + +/** + * disables the pin probe mcu isr on change + * can be defined either as a function or a macro call + * */ +#ifndef mcu_disable_probe_isr +void mcu_disable_probe_isr(void); +#endif + +/** + * gets the voltage value of a built-in ADC pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_analog +uint8_t mcu_get_analog(uint8_t channel); +#endif + +/** + * sets the pwm value of a built-in pwm pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_set_pwm +void mcu_set_pwm(uint8_t pwm, uint8_t value); +#endif + +/** + * gets the configured pwm value of a built-in pwm pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_pwm +uint8_t mcu_get_pwm(uint8_t pwm); +#endif + +/** + * checks if the serial hardware of the MCU is ready do send the next char + * */ +#ifndef mcu_tx_ready +bool mcu_tx_ready(void); // Start async send +#endif + +/** + * checks if the serial hardware of the MCU has a new char ready to be read + * */ +#ifndef mcu_rx_ready +bool mcu_rx_ready(void); // Stop async send +#endif + +/** + * sends a char either via uart (hardware, software or USB virtual COM port) + * can be defined either as a function or a macro call + * */ +#ifndef mcu_putc +void mcu_putc(char c); +#endif + +/** + * gets a char either via uart (hardware, software or USB virtual COM port) + * can be defined either as a function or a macro call + * */ +#ifndef mcu_getc +char mcu_getc(void); +#endif + +// ISR +/** + * enables global interrupts on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_enable_global_isr +void mcu_enable_global_isr(void); +#endif + +/** + * disables global interrupts on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_disable_global_isr +void mcu_disable_global_isr(void); +#endif + +/** + * gets global interrupts state on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_global_isr +bool mcu_get_global_isr(void); +#endif + +// Step interpolator +/** + * convert step rate to clock cycles + * */ +void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller); + +/** + * starts the timer interrupt that generates the step pulses for the interpolator + * */ +void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller); + +/** + * changes the step rate of the timer interrupt that generates the step pulses for the interpolator + * */ +void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller); + +/** + * stops the timer interrupt that generates the step pulses for the interpolator + * */ +void mcu_stop_itp_isr(void); + +/** + * gets the MCU running time in milliseconds. + * the time counting is controled by the internal RTC + * */ +uint32_t mcu_millis(); + +/** + * runs all internal tasks of the MCU. + * for the moment these are: + * - if USB is enabled and MCU uses tinyUSB framework run tinyUSB tud_task + * - if ENABLE_SYNC_RX is enabled check if there are any chars in the rx transmitter (or the tinyUSB buffer) and read them to the serial_rx_isr + * - if ENABLE_SYNC_TX is enabled check if serial_tx_empty is false and run serial_tx_isr + * */ +void mcu_dotasks(void); + +// Non volatile memory +/** + * gets a byte at the given EEPROM (or other non volatile memory) address of the MCU. + * */ +uint8_t mcu_eeprom_getc(uint16_t address); + +/** + * sets a byte at the given EEPROM (or other non volatile memory) address of the MCU. + * */ +void mcu_eeprom_putc(uint16_t address, uint8_t value); + +/** + * flushes all recorded registers into the eeprom. + * */ +void mcu_eeprom_flush(void); + +#endif diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h new file mode 100644 index 000000000..86885d126 --- /dev/null +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -0,0 +1,700 @@ +/* + Name: mcumap_esp8266.h + Description: Contains all MCU and PIN definitions for Arduino ESP8266 to run µCNC. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 04-02-2020 + + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#ifndef MCUMAP_ESP8266_H +#define MCUMAP_ESP8266_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/* + Generates all the interface definitions. + This creates a middle HAL layer between the board IO pins and the AVR funtionalities +*/ +/* + MCU specific definitions and replacements +*/ + +/* + AVR Defaults +*/ +// defines the frequency of the mcu +#ifndef F_CPU +#define F_CPU 80000000UL +#endif +// defines the maximum and minimum step rates +#ifndef F_STEP_MAX +#define F_STEP_MAX 100000 +#endif +#ifndef F_STEP_MIN +#define F_STEP_MIN 4 +#endif + +// defines special mcu to access flash strings and arrays +#define __rom__ PROGMEM +#define __romstr__ PSTR +#define rom_strptr pgm_read_byte +#define rom_strcpy strcpy_P +#define rom_strncpy strncpy_P +#define rom_memcpy memcpy_P +#define rom_read_byte pgm_read_byte + +#define __SIZEOF_FLOAT__ 4 + +// used by the parser +// this method is faster then normal multiplication (for 32 bit for 16 and 8 bits is slightly lower) +// overrides utils.h definition to implement this method with or without fast math option enabled +#define fast_int_mul10(x) ((((x) << 2) + (x)) << 1) + +#if (defined(STEP0_BIT)) +#define DIO0 0 +#define STEP0 0 +#define DIO0_BIT (STEP0_BIT) +#endif +#if (defined(STEP1_BIT)) +#define DIO1 1 +#define STEP1 1 +#define DIO1_BIT (STEP1_BIT) +#endif +#if (defined(STEP2_BIT)) +#define DIO2 2 +#define STEP2 2 +#define DIO2_BIT (STEP2_BIT) +#endif +#if (defined(STEP3_BIT)) +#define DIO3 3 +#define STEP3 3 +#define DIO3_BIT (STEP3_BIT) +#endif +#if (defined(STEP4_BIT)) +#define DIO4 4 +#define STEP4 4 +#define DIO4_BIT (STEP4_BIT) +#endif +#if (defined(STEP5_BIT)) +#define DIO5 5 +#define STEP5 5 +#define DIO5_BIT (STEP5_BIT) +#endif +#if (defined(STEP6_BIT)) +#define DIO6 6 +#define STEP6 6 +#define DIO6_BIT (STEP6_BIT) +#endif +#if (defined(STEP7_BIT)) +#define DIO7 7 +#define STEP7 7 +#define DIO7_BIT (STEP7_BIT) +#endif +#if (defined(DIR0_BIT)) +#define DIO8 8 +#define DIR0 8 +#define DIO8_BIT (DIR0_BIT) +#endif +#if (defined(DIR1_BIT)) +#define DIO9 9 +#define DIR1 9 +#define DIO9_BIT (DIR1_BIT) +#endif +#if (defined(DIR2_BIT)) +#define DIO10 10 +#define DIR2 10 +#define DIO10_BIT (DIR2_BIT) +#endif +#if (defined(DIR3_BIT)) +#define DIO11 11 +#define DIR3 11 +#define DIO11_BIT (DIR3_BIT) +#endif +#if (defined(DIR4_BIT)) +#define DIO12 12 +#define DIR4 12 +#define DIO12_BIT (DIR4_BIT) +#endif +#if (defined(DIR5_BIT)) +#define DIO13 13 +#define DIR5 13 +#define DIO13_BIT (DIR5_BIT) +#endif +#if (defined(STEP0_EN_BIT)) +#define DIO14 14 +#define STEP0_EN 14 +#define DIO14_BIT (STEP0_EN_BIT) +#endif +#if (defined(STEP1_EN_BIT)) +#define DIO15 15 +#define STEP1_EN 15 +#define DIO15_BIT (STEP1_EN_BIT) +#endif +#if (defined(STEP2_EN_BIT)) +#define DIO16 16 +#define STEP2_EN 16 +#define DIO16_BIT (STEP2_EN_BIT) +#endif +#if (defined(STEP3_EN_BIT)) +#define DIO17 17 +#define STEP3_EN 17 +#define DIO17_BIT (STEP3_EN_BIT) +#endif +#if (defined(STEP4_EN_BIT)) +#define DIO18 18 +#define STEP4_EN 18 +#define DIO18_BIT (STEP4_EN_BIT) +#endif +#if (defined(STEP5_EN_BIT)) +#define DIO19 19 +#define STEP5_EN 19 +#define DIO19_BIT (STEP5_EN_BIT) +#endif +#if (defined(PWM0_BIT)) +#define DIO20 20 +#define PWM0 20 +#define DIO20_BIT (PWM0_BIT) +#endif +#if (defined(PWM1_BIT)) +#define DIO21 21 +#define PWM1 21 +#define DIO21_BIT (PWM1_BIT) +#endif +#if (defined(PWM2_BIT)) +#define DIO22 22 +#define PWM2 22 +#define DIO22_BIT (PWM2_BIT) +#endif +#if (defined(PWM3_BIT)) +#define DIO23 23 +#define PWM3 23 +#define DIO23_BIT (PWM3_BIT) +#endif +#if (defined(PWM4_BIT)) +#define DIO24 24 +#define PWM4 24 +#define DIO24_BIT (PWM4_BIT) +#endif +#if (defined(PWM5_BIT)) +#define DIO25 25 +#define PWM5 25 +#define DIO25_BIT (PWM5_BIT) +#endif +#if (defined(PWM6_BIT)) +#define DIO26 26 +#define PWM6 26 +#define DIO26_BIT (PWM6_BIT) +#endif +#if (defined(PWM7_BIT)) +#define DIO27 27 +#define PWM7 27 +#define DIO27_BIT (PWM7_BIT) +#endif +#if (defined(PWM8_BIT)) +#define DIO28 28 +#define PWM8 28 +#define DIO28_BIT (PWM8_BIT) +#endif +#if (defined(PWM9_BIT)) +#define DIO29 29 +#define PWM9 29 +#define DIO29_BIT (PWM9_BIT) +#endif +#if (defined(PWM10_BIT)) +#define DIO30 30 +#define PWM10 30 +#define DIO30_BIT (PWM10_BIT) +#endif +#if (defined(PWM11_BIT)) +#define DIO31 31 +#define PWM11 31 +#define DIO31_BIT (PWM11_BIT) +#endif +#if (defined(PWM12_BIT)) +#define DIO32 32 +#define PWM12 32 +#define DIO32_BIT (PWM12_BIT) +#endif +#if (defined(PWM13_BIT)) +#define DIO33 33 +#define PWM13 33 +#define DIO33_BIT (PWM13_BIT) +#endif +#if (defined(PWM14_BIT)) +#define DIO34 34 +#define PWM14 34 +#define DIO34_BIT (PWM14_BIT) +#endif +#if (defined(PWM15_BIT)) +#define DIO35 35 +#define PWM15 35 +#define DIO35_BIT (PWM15_BIT) +#endif +#if (defined(DOUT0_BIT)) +#define DIO36 36 +#define DOUT0 36 +#define DIO36_BIT (DOUT0_BIT) +#endif +#if (defined(DOUT1_BIT)) +#define DIO37 37 +#define DOUT1 37 +#define DIO37_BIT (DOUT1_BIT) +#endif +#if (defined(DOUT2_BIT)) +#define DIO38 38 +#define DOUT2 38 +#define DIO38_BIT (DOUT2_BIT) +#endif +#if (defined(DOUT3_BIT)) +#define DIO39 39 +#define DOUT3 39 +#define DIO39_BIT (DOUT3_BIT) +#endif +#if (defined(DOUT4_BIT)) +#define DIO40 40 +#define DOUT4 40 +#define DIO40_BIT (DOUT4_BIT) +#endif +#if (defined(DOUT5_BIT)) +#define DIO41 41 +#define DOUT5 41 +#define DIO41_BIT (DOUT5_BIT) +#endif +#if (defined(DOUT6_BIT)) +#define DIO42 42 +#define DOUT6 42 +#define DIO42_BIT (DOUT6_BIT) +#endif +#if (defined(DOUT7_BIT)) +#define DIO43 43 +#define DOUT7 43 +#define DIO43_BIT (DOUT7_BIT) +#endif +#if (defined(DOUT8_BIT)) +#define DIO44 44 +#define DOUT8 44 +#define DIO44_BIT (DOUT8_BIT) +#endif +#if (defined(DOUT9_BIT)) +#define DIO45 45 +#define DOUT9 45 +#define DIO45_BIT (DOUT9_BIT) +#endif +#if (defined(DOUT10_BIT)) +#define DIO46 46 +#define DOUT10 46 +#define DIO46_BIT (DOUT10_BIT) +#endif +#if (defined(DOUT11_BIT)) +#define DIO47 47 +#define DOUT11 47 +#define DIO47_BIT (DOUT11_BIT) +#endif +#if (defined(DOUT12_BIT)) +#define DIO48 48 +#define DOUT12 48 +#define DIO48_BIT (DOUT12_BIT) +#endif +#if (defined(DOUT13_BIT)) +#define DIO49 49 +#define DOUT13 49 +#define DIO49_BIT (DOUT13_BIT) +#endif +#if (defined(DOUT14_BIT)) +#define DIO50 50 +#define DOUT14 50 +#define DIO50_BIT (DOUT14_BIT) +#endif +#if (defined(DOUT15_BIT)) +#define DIO51 51 +#define DOUT15 51 +#define DIO51_BIT (DOUT15_BIT) +#endif +#if (defined(LIMIT_X_BIT)) +#define DIO52 52 +#define LIMIT_X 52 +#define DIO52_BIT (LIMIT_X_BIT) +#endif +#if (defined(LIMIT_Y_BIT)) +#define DIO53 53 +#define LIMIT_Y 53 +#define DIO53_BIT (LIMIT_Y_BIT) +#endif +#if (defined(LIMIT_Z_BIT)) +#define DIO54 54 +#define LIMIT_Z 54 +#define DIO54_BIT (LIMIT_Z_BIT) +#endif +#if (defined(LIMIT_X2_BIT)) +#define DIO55 55 +#define LIMIT_X2 55 +#define DIO55_BIT (LIMIT_X2_BIT) +#endif +#if (defined(LIMIT_Y2_BIT)) +#define DIO56 56 +#define LIMIT_Y2 56 +#define DIO56_BIT (LIMIT_Y2_BIT) +#endif +#if (defined(LIMIT_Z2_BIT)) +#define DIO57 57 +#define LIMIT_Z2 57 +#define DIO57_BIT (LIMIT_Z2_BIT) +#endif +#if (defined(LIMIT_A_BIT)) +#define DIO58 58 +#define LIMIT_A 58 +#define DIO58_BIT (LIMIT_A_BIT) +#endif +#if (defined(LIMIT_B_BIT)) +#define DIO59 59 +#define LIMIT_B 59 +#define DIO59_BIT (LIMIT_B_BIT) +#endif +#if (defined(LIMIT_C_BIT)) +#define DIO60 60 +#define LIMIT_C 60 +#define DIO60_BIT (LIMIT_C_BIT) +#endif +#if (defined(PROBE_BIT)) +#define DIO61 61 +#define PROBE 61 +#define DIO61_BIT (PROBE_BIT) +#endif +#if (defined(ESTOP_BIT)) +#define DIO62 62 +#define ESTOP 62 +#define DIO62_BIT (ESTOP_BIT) +#endif +#if (defined(SAFETY_DOOR_BIT)) +#define DIO63 63 +#define SAFETY_DOOR 63 +#define DIO63_BIT (SAFETY_DOOR_BIT) +#endif +#if (defined(FHOLD_BIT)) +#define DIO64 64 +#define FHOLD 64 +#define DIO64_BIT (FHOLD_BIT) +#endif +#if (defined(CS_RES_BIT)) +#define DIO65 65 +#define CS_RES 65 +#define DIO65_BIT (CS_RES_BIT) +#endif +#if (defined(ANALOG0_BIT)) +#define DIO66 66 +#define ANALOG0 66 +#define DIO66_BIT (ANALOG0_BIT) +#endif +#if (defined(ANALOG1_BIT)) +#define DIO67 67 +#define ANALOG1 67 +#define DIO67_BIT (ANALOG1_BIT) +#endif +#if (defined(ANALOG2_BIT)) +#define DIO68 68 +#define ANALOG2 68 +#define DIO68_BIT (ANALOG2_BIT) +#endif +#if (defined(ANALOG3_BIT)) +#define DIO69 69 +#define ANALOG3 69 +#define DIO69_BIT (ANALOG3_BIT) +#endif +#if (defined(ANALOG4_BIT)) +#define DIO70 70 +#define ANALOG4 70 +#define DIO70_BIT (ANALOG4_BIT) +#endif +#if (defined(ANALOG5_BIT)) +#define DIO71 71 +#define ANALOG5 71 +#define DIO71_BIT (ANALOG5_BIT) +#endif +#if (defined(ANALOG6_BIT)) +#define DIO72 72 +#define ANALOG6 72 +#define DIO72_BIT (ANALOG6_BIT) +#endif +#if (defined(ANALOG7_BIT)) +#define DIO73 73 +#define ANALOG7 73 +#define DIO73_BIT (ANALOG7_BIT) +#endif +#if (defined(ANALOG8_BIT)) +#define DIO74 74 +#define ANALOG8 74 +#define DIO74_BIT (ANALOG8_BIT) +#endif +#if (defined(ANALOG9_BIT)) +#define DIO75 75 +#define ANALOG9 75 +#define DIO75_BIT (ANALOG9_BIT) +#endif +#if (defined(ANALOG10_BIT)) +#define DIO76 76 +#define ANALOG10 76 +#define DIO76_BIT (ANALOG10_BIT) +#endif +#if (defined(ANALOG11_BIT)) +#define DIO77 77 +#define ANALOG11 77 +#define DIO77_BIT (ANALOG11_BIT) +#endif +#if (defined(ANALOG12_BIT)) +#define DIO78 78 +#define ANALOG12 78 +#define DIO78_BIT (ANALOG12_BIT) +#endif +#if (defined(ANALOG13_BIT)) +#define DIO79 79 +#define ANALOG13 79 +#define DIO79_BIT (ANALOG13_BIT) +#endif +#if (defined(ANALOG14_BIT)) +#define DIO80 80 +#define ANALOG14 80 +#define DIO80_BIT (ANALOG14_BIT) +#endif +#if (defined(ANALOG15_BIT)) +#define DIO81 81 +#define ANALOG15 81 +#define DIO81_BIT (ANALOG15_BIT) +#endif +#if (defined(DIN0_BIT)) +#define DIO82 82 +#define DIN0 82 +#define DIO82_BIT (DIN0_BIT) +#endif +#if (defined(DIN1_BIT)) +#define DIO83 83 +#define DIN1 83 +#define DIO83_BIT (DIN1_BIT) +#endif +#if (defined(DIN2_BIT)) +#define DIO84 84 +#define DIN2 84 +#define DIO84_BIT (DIN2_BIT) +#endif +#if (defined(DIN3_BIT)) +#define DIO85 85 +#define DIN3 85 +#define DIO85_BIT (DIN3_BIT) +#endif +#if (defined(DIN4_BIT)) +#define DIO86 86 +#define DIN4 86 +#define DIO86_BIT (DIN4_BIT) +#endif +#if (defined(DIN5_BIT)) +#define DIO87 87 +#define DIN5 87 +#define DIO87_BIT (DIN5_BIT) +#endif +#if (defined(DIN6_BIT)) +#define DIO88 88 +#define DIN6 88 +#define DIO88_BIT (DIN6_BIT) +#endif +#if (defined(DIN7_BIT)) +#define DIO89 89 +#define DIN7 89 +#define DIO89_BIT (DIN7_BIT) +#endif +#if (defined(DIN8_BIT)) +#define DIO90 90 +#define DIN8 90 +#define DIO90_BIT (DIN8_BIT) +#endif +#if (defined(DIN9_BIT)) +#define DIO91 91 +#define DIN9 91 +#define DIO91_BIT (DIN9_BIT) +#endif +#if (defined(DIN10_BIT)) +#define DIO92 92 +#define DIN10 92 +#define DIO92_BIT (DIN10_BIT) +#endif +#if (defined(DIN11_BIT)) +#define DIO93 93 +#define DIN11 93 +#define DIO93_BIT (DIN11_BIT) +#endif +#if (defined(DIN12_BIT)) +#define DIO94 94 +#define DIN12 94 +#define DIO94_BIT (DIN12_BIT) +#endif +#if (defined(DIN13_BIT)) +#define DIO95 95 +#define DIN13 95 +#define DIO95_BIT (DIN13_BIT) +#endif +#if (defined(DIN14_BIT)) +#define DIO96 96 +#define DIN14 96 +#define DIO96_BIT (DIN14_BIT) +#endif +#if (defined(DIN15_BIT)) +#define DIO97 97 +#define DIN15 97 +#define DIO97_BIT (DIN15_BIT) +#endif +#if (defined(TX_BIT)) +#define DIO98 98 +#define TX 98 +#define DIO98_BIT (TX_BIT) +#endif +#if (defined(RX_BIT)) +#define DIO99 99 +#define RX 99 +#define DIO99_BIT (RX_BIT) +#endif + +// ISR on change inputs +#if (defined(LIMIT_X_ISR) && defined(LIMIT_X)) +#define DIO52_ISR (LIMIT_X_ISR) +#define LIMIT_X_ISRCALLBACK mcu_limit_isr +#define DIO52_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_Y_ISR) && defined(LIMIT_Y)) +#define DIO53_ISR (LIMIT_Y_ISR) +#define LIMIT_Y_ISRCALLBACK mcu_limit_isr +#define DIO53_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_Z_ISR) && defined(LIMIT_Z)) +#define DIO54_ISR (LIMIT_Z_ISR) +#define LIMIT_Z_ISRCALLBACK mcu_limit_isr +#define DIO54_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_X2_ISR) && defined(LIMIT_X2)) +#define DIO55_ISR (LIMIT_X2_ISR) +#define LIMIT_X2_ISRCALLBACK mcu_limit_isr +#define DIO55_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_Y2_ISR) && defined(LIMIT_Y2)) +#define DIO56_ISR (LIMIT_Y2_ISR) +#define LIMIT_Y2_ISRCALLBACK mcu_limit_isr +#define DIO56_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_Z2_ISR) && defined(LIMIT_Z2)) +#define DIO57_ISR (LIMIT_Z2_ISR) +#define LIMIT_Z2_ISRCALLBACK mcu_limit_isr +#define DIO57_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_A_ISR) && defined(LIMIT_A)) +#define DIO58_ISR (LIMIT_A_ISR) +#define LIMIT_A_ISRCALLBACK mcu_limit_isr +#define DIO58_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_B_ISR) && defined(LIMIT_B)) +#define DIO59_ISR (LIMIT_B_ISR) +#define LIMIT_B_ISRCALLBACK mcu_limit_isr +#define DIO59_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(LIMIT_C_ISR) && defined(LIMIT_C)) +#define DIO60_ISR (LIMIT_C_ISR) +#define LIMIT_C_ISRCALLBACK mcu_limit_isr +#define DIO60_ISRCALLBACK mcu_limit_isr +#endif +#if (defined(PROBE_ISR) && defined(PROBE)) +#define DIO61_ISR (PROBE_ISR) +#define PROBE_ISRCALLBACK mcu_probe_isr +#define DIO61_ISRCALLBACK mcu_probe_isr +#endif +#if (defined(ESTOP_ISR) && defined(ESTOP)) +#define DIO62_ISR (ESTOP_ISR) +#define ESTOP_ISRCALLBACK mcu_control_isr +#define DIO62_ISRCALLBACK mcu_control_isr +#endif +#if (defined(SAFETY_DOOR_ISR) && defined(SAFETY_DOOR)) +#define DIO63_ISR (SAFETY_DOOR_ISR) +#define SAFETY_DOOR_ISRCALLBACK mcu_control_isr +#define DIO63_ISRCALLBACK mcu_control_isr +#endif +#if (defined(FHOLD_ISR) && defined(FHOLD)) +#define DIO64_ISR (FHOLD_ISR) +#define FHOLD_ISRCALLBACK mcu_control_isr +#define DIO64_ISRCALLBACK mcu_control_isr +#endif +#if (defined(CS_RES_ISR) && defined(CS_RES)) +#define DIO65_ISR (CS_RES_ISR) +#define CS_RES_ISRCALLBACK mcu_control_isr +#define DIO65_ISRCALLBACK mcu_control_isr +#endif +#if (defined(DIN0_ISR) && defined(DIN0)) +#define DIO82_ISR (DIN0_ISR) +#define DIN0_ISRCALLBACK mcu_din_isr +#define DIO82_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN1_ISR) && defined(DIN1)) +#define DIO83_ISR (DIN1_ISR) +#define DIN1_ISRCALLBACK mcu_din_isr +#define DIO83_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN2_ISR) && defined(DIN2)) +#define DIO84_ISR (DIN2_ISR) +#define DIN2_ISRCALLBACK mcu_din_isr +#define DIO84_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN3_ISR) && defined(DIN3)) +#define DIO85_ISR (DIN3_ISR) +#define DIN3_ISRCALLBACK mcu_din_isr +#define DIO85_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN4_ISR) && defined(DIN4)) +#define DIO86_ISR (DIN4_ISR) +#define DIN4_ISRCALLBACK mcu_din_isr +#define DIO86_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN5_ISR) && defined(DIN5)) +#define DIO87_ISR (DIN5_ISR) +#define DIN5_ISRCALLBACK mcu_din_isr +#define DIO87_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN6_ISR) && defined(DIN6)) +#define DIO88_ISR (DIN6_ISR) +#define DIN6_ISRCALLBACK mcu_din_isr +#define DIO88_ISRCALLBACK mcu_din_isr +#endif +#if (defined(DIN7_ISR) && defined(DIN7)) +#define DIO89_ISR (DIN7_ISR) +#define DIN7_ISRCALLBACK mcu_din_isr +#define DIO89_ISRCALLBACK mcu_din_isr +#endif + +// Helper macros +#define __helper_ex__(left, mid, right) (left##mid##right) +#define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) + +#define mcu_config_output(X) pinMode(__helper__(X, _BIT, ), OUTPUT) +#define mcu_config_pwm(X) analogWriteMode(__helper__(X, _BIT, ), 0, OUTPUT_OPEN_DRAIN) +#define mcu_config_pwm(X) analogWriteMode(__helper__(X, _BIT, ), 0, OUTPUT_OPEN_DRAIN) +#define mcu_config_input(X) pinMode(__helper__(X, _BIT, ), INPUT) +#define mcu_config_pullup(X) pinMode(__helper__(X, _BIT, ), INPUT_PULLUP) +#define mcu_config_input_isr(X) attachInterrupt(digitalPinToInterrupt(__helper__(X, _BIT, )), __helper__(X, _ISRCALLBACK, ), CHANGE) + +#define mcu_get_input(X) digitalRead(__helper__(X, _BIT, )) +#define mcu_get_output(X) digitalRead(__helper__(X, _BIT, )) +#define mcu_set_output(X) digitalWrite(__helper__(X, _BIT, ), 1) +#define mcu_clear_output(X) digitalWrite(__helper__(X, _BIT, ), 0) +#define mcu_toggle_output(X) digitalWrite(__helper__(X, _BIT, ), !digitalRead(__helper__(X, _BIT, ))) + +#ifdef __cplusplus +} +#endif + +#endif From bfa54a4139fc7b6adf02ab1842a4ae2f1feec614 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 24 Jun 2022 08:54:46 +0100 Subject: [PATCH 02/13] ESP8266 core support -UART working -Step timer working -RTC needs testing --- platformio.ini | 14 + uCNC/src/cnc_build.h | 4 +- uCNC/src/hal/boards/boarddefs.h | 10 + uCNC/src/hal/boards/boards.h | 2 + .../hal/boards/esp8266/boardmap_wemos_d1.h | 86 ++ uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp | 38 + uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 135 ++ uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 647 ++++++++- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 1154 +++++++++++------ uCNC/src/hal/mcus/mcudefs.h | 14 + uCNC/src/hal/mcus/mcus.h | 2 + uCNC/uCNC.ino | 15 +- 12 files changed, 1722 insertions(+), 399 deletions(-) create mode 100644 uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h create mode 100644 uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp create mode 100644 uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp diff --git a/platformio.ini b/platformio.ini index 93a073d8b..5c4767902 100644 --- a/platformio.ini +++ b/platformio.ini @@ -88,3 +88,17 @@ platform = ststm32 board = blackpill_f401cc framework = arduino build_flags = -D BOARD=BOARD_BLACKPILL -D INTERFACE=1 -D HAL_TIM_MODULE_DISABLED -D HAL_EXTI_MODULE_DISABLED -fdata-sections -ffunction-sections -Wl,--gc-sections + +[env:re_arm] +platform = nxplpc +board = lpc1768 +framework = mbed +build_flags = -D BOARD=BOARD_RE_ARM -D INTERFACE=1 -fdata-sections -ffunction-sections -Wl,--gc-sections + +[env:d1] +platform = espressif8266 +framework = arduino +board = d1 +lib_deps = + WiFiManager +build_flags = -I include -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index 8a527f788..ca6461161 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -24,8 +24,8 @@ extern "C" { #endif -#define CNC_MAJOR_MINOR_VERSION "1.4" -#define CNC_PATCH_VERSION ".6pre" +#define CNC_MAJOR_MINOR_VERSION "1.5" +#define CNC_PATCH_VERSION ".alpha" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION diff --git a/uCNC/src/hal/boards/boarddefs.h b/uCNC/src/hal/boards/boarddefs.h index dfe5aa203..decac884b 100644 --- a/uCNC/src/hal/boards/boarddefs.h +++ b/uCNC/src/hal/boards/boarddefs.h @@ -93,6 +93,16 @@ extern "C" #include "samd21/boardmap_zero.h" #endif +#if (BOARD == BOARD_RE_ARM) +#define MCU MCU_LPC176X +#include "lpc176x/boardmap_re_arm.h" +#endif + +#if (BOARD == BOARD_WEMOS_D1) +#define MCU MCU_ESP8266 +#include "esp8266/boardmap_wemos_d1.h" +#endif + #if (BOARD == BOARD_VIRTUAL) #ifndef __linux__ #define MCU MCU_VIRTUAL_WIN diff --git a/uCNC/src/hal/boards/boards.h b/uCNC/src/hal/boards/boards.h index 4c340c684..72cd051b1 100644 --- a/uCNC/src/hal/boards/boards.h +++ b/uCNC/src/hal/boards/boards.h @@ -34,6 +34,8 @@ extern "C" #define BOARD_BLACKPILL 11 #define BOARD_MZERO 20 #define BOARD_ZERO 21 +#define BOARD_RE_ARM 30 +#define BOARD_WEMOS_D1 40 #define BOARD_VIRTUAL 99 // special purpose board diff --git a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h new file mode 100644 index 000000000..50447d3f8 --- /dev/null +++ b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h @@ -0,0 +1,86 @@ +/* + Name: boardmap_wemos_d1.h + Description: Contains all MCU and PIN definitions for Arduino WeMos D1 to run µCNC. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 17/06/2022 + + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#ifndef BOARDMAP_WEMOS_D1_H +#define BOARDMAP_WEMOS_D1_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#ifndef BOARD_NAME +#define BOARD_NAME "WEMOS D1" +#endif + +// SAME AS GRBL for test purposes +// Setup step pins +#define STEP2_BIT 4 // assigns STEP2 pin +#define STEP2_PORT D // assigns STEP2 port +#define STEP1_BIT 5 // assigns STEP1 pin +#define STEP1_PORT D // assigns STEP1 port +#define STEP0_BIT 16 // assigns STEP0 pin +#define STEP0_PORT D // assigns STEP0 port + +// Setup dir pins +#define DIR2_BIT 13 // assigns DIR2 pin +#define DIR2_PORT D // assigns DIR2 port +#define DIR1_BIT 12 // assigns DIR1 pin +#define DIR1_PORT D // assigns DIR1 port +#define DIR0_BIT 14 // assigns DIR0 pin +#define DIR0_PORT D // assigns DIR0 port + +// Setup control input pins +// #define ESTOP_BIT 0 +// #define ESTOP_PORT A +//#define ESTOP_ISR + +// Setup com pins +#define RX_BIT 3 +#define TX_BIT 1 +#define RX_PORT D +#define TX_PORT D + // only uncomment this if other port other then 0 is used + //#define COM_PORT 0 + + // Setup PWM +#define PWM0_BIT 2 // assigns PWM0 pin +#define PWM0_PORT D // assigns PWM0 pin + +// Setup generic IO Pins +// spindle dir +#define DOUT0_BIT 15 +#define DOUT0_PORT D + +// Stepper enable pin. For Grbl on Uno board a single pin is used +#define STEP0_EN_BIT 0 +#define STEP0_EN_PORT D + + // Setup the Step Timer used has the heartbeat for µCNC + // Timer 1 is used by default + //#define ITP_TIMER 1 + + // Setup the RTC Timer used by µCNC to provide an (mostly) accurate time base for all time dependent functions + // Timer 0 is set by default + //#define RTC_TIMER 0 + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp new file mode 100644 index 000000000..2c1f9f5b5 --- /dev/null +++ b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp @@ -0,0 +1,38 @@ +#include "../../../../cnc_config.h" +#include +#include + +extern "C" +{ + void esp8266_uart_init(int baud) + { + Serial.begin(baud); + } + + char esp8266_uart_read(void) + { + return Serial.read(); + } + + void esp8266_uart_write(char c) + { + Serial.write(c); + } + + bool esp8266_uart_rx_ready(void) + { + return (Serial.available() != 0); + } + + bool esp8266_uart_tx_ready(void) + { + return (Serial.availableForWrite() != 0); + } + + void esp8266_uart_flush(void) + { + Serial.flush(); + } + + void mcu_com_rx_cb(unsigned char c); +} diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp new file mode 100644 index 000000000..bd2e192f0 --- /dev/null +++ b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp @@ -0,0 +1,135 @@ +//#include "Arduino.h" +#include "../../../../cnc_config.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifndef WIFI_BUFFER +#define WIFI_BUFFER 128 +#endif + +#ifndef WIFI_PORT +#define WIFI_PORT 23 +#endif + +#ifndef WIFI_USER +#define WIFI_USER "admin" +#endif + +#ifndef WIFI_PASS +#define WIFI_PASS "pass" +#endif + +ESP8266WebServer httpServer(80); +ESP8266HTTPUpdateServer httpUpdater; +const char *update_path = "/firmware"; +const char *update_username = WIFI_USER; +const char *update_password = WIFI_PASS; +#define MAX_SRV_CLIENTS 1 +WiFiServer server(WIFI_PORT); +WiFiClient serverClient; +WiFiManager wifiManager; + +extern "C" +{ + void esp8266_wifi_init(void) + { +#ifdef WIFI_DEBUG + Serial.begin(115200); + wifiManager.setDebugOutput(true); +#else + wifiManager.setDebugOutput(false); +#endif + wifiManager.autoConnect("ESP8266"); +#ifdef WIFI_DEBUG + Serial.println("[MSG: WiFi manager up]"); +#endif +#ifdef WIFI_DEBUG + Serial.println("[MSG: Setup page @ 192.168.4.1]"); +#endif + server.setNoDelay(true); + httpUpdater.setup(&httpServer, update_path, update_username, update_password); + httpServer.begin(); + WiFi.setSleepMode(WIFI_NONE_SLEEP); + +#ifdef WIFI_DEBUG + Serial.println("[MSG: WiFi server us up]"); +#endif + } + + void esp8266_wifi_read(void (*read_callback)(unsigned char)) + { + if (server.hasClient()) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: client waiting]"); +#endif + if (serverClient && serverClient.connected()) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: kill old client]"); +#endif + serverClient.stop(); + } + +#ifdef WIFI_DEBUG + Serial.println("[MSG: client started]"); +#endif + } + else if (serverClient && serverClient.connected()) + { + size_t rxlen = serverClient.available(); + if (rxlen > 0) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: client has data]"); +#endif + uint8_t sbuf[rxlen]; + serverClient.readBytes(sbuf, rxlen); + for (uint8_t i = 0; i < rxlen; i++) + { + if (read_callback) + { + read_callback((unsigned char)sbuf[i]); + } + yield(); + } + } + } + } + + void esp8266_wifi_write(char *buff, uint8_t len) + { + if (server.hasClient()) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: client waiting]"); +#endif + if (serverClient && serverClient.connected()) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: kill old client]"); +#endif + serverClient.stop(); + } + +#ifdef WIFI_DEBUG + Serial.println("[MSG: client started]"); +#endif + } + else if (serverClient && serverClient.connected()) + { +#ifdef WIFI_DEBUG + Serial.println("[MSG: sent data to client]"); +#endif + serverClient.write(buff, (size_t)len); + } + } +} diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 0562d126f..88a8a0e58 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -20,12 +20,42 @@ #if (MCU == MCU_ESP8266) -#include "Arduino.h" -#include - #include #include #include +#include +#include "ets_sys.h" +#include "os_type.h" +#include "gpio.h" +#include "eagle_soc.h" +#include "uart_register.h" +#include "osapi.h" + +#define UART_PARITY_EN (BIT(1)) +#define UART_PARITY_EN_M 0x00000001 +#define UART_PARITY_EN_S 1 +#define UART_PARITY (BIT(0)) +#define UART_PARITY_M 0x00000001 +#define UART_PARITY_S 0 + +static volatile bool esp8266_global_isr_enabled; +static volatile uint32_t mcu_runtime_ms; +uint8_t esp8266_pwm[16]; + +char esp8266_tx_buffer[TX_BUFFER_SIZE - 2]; +char esp8266_rx_buffer[RX_BUFFER_SIZE]; +char *tx_ptr; +void esp8266_wifi_init(void); +void esp8266_wifi_read(void (*read_callback)(unsigned char)); +void esp8266_wifi_write(char *buff, uint8_t len); +void esp8266_uart_init(int baud); +char esp8266_uart_read(void); +void esp8266_uart_write(char c); +bool esp8266_uart_rx_ready(void); +bool esp8266_uart_tx_ready(void); +void esp8266_uart_flush(void); + +ETSTimer esp8266_rtc_timer; IRAM_ATTR void mcu_din_isr(void) { @@ -47,6 +77,231 @@ IRAM_ATTR void mcu_controls_isr(void) io_controls_isr(); } +IRAM_ATTR void mcu_rtc_isr(void *arg) +{ + static uint8_t pwm_counter = 0; + mcu_runtime_ms++; + // software PWM + if (++pwm_counter) + { +#if !(PWM0 < 0) + if (pwm_counter > esp8266_pwm[0]) + { + mcu_clear_output(PWM0); + } +#endif +#if !(PWM1 < 0) + if (pwm_counter > esp8266_pwm[1]) + { + mcu_clear_output(PWM1); + } +#endif +#if !(PWM2 < 0) + if (pwm_counter > esp8266_pwm[2]) + { + mcu_clear_output(PWM2); + } +#endif +#if !(PWM3 < 0) + if (pwm_counter > esp8266_pwm[3]) + { + mcu_clear_output(PWM3); + } +#endif +#if !(PWM4 < 0) + if (pwm_counter > esp8266_pwm[4]) + { + mcu_clear_output(PWM4); + } +#endif +#if !(PWM5 < 0) + if (pwm_counter > esp8266_pwm[5]) + { + mcu_clear_output(PWM5); + } +#endif +#if !(PWM6 < 0) + if (pwm_counter > esp8266_pwm[6]) + { + mcu_clear_output(PWM6); + } +#endif +#if !(PWM7 < 0) + if (pwm_counter > esp8266_pwm[7]) + { + mcu_clear_output(PWM7); + } +#endif +#if !(PWM8 < 0) + if (pwm_counter > esp8266_pwm[8]) + { + mcu_clear_output(PWM8); + } +#endif +#if !(PWM9 < 0) + if (pwm_counter > esp8266_pwm[9]) + { + mcu_clear_output(PWM9); + } +#endif +#if !(PWM10 < 0) + if (pwm_counter > esp8266_pwm[10]) + { + mcu_clear_output(PWM10); + } +#endif +#if !(PWM11 < 0) + if (pwm_counter > esp8266_pwm[11]) + { + mcu_clear_output(PWM11); + } +#endif +#if !(PWM12 < 0) + if (pwm_counter > esp8266_pwm[12]) + { + mcu_clear_output(PWM12); + } +#endif +#if !(PWM13 < 0) + if (pwm_counter > esp8266_pwm[13]) + { + mcu_clear_output(PWM13); + } +#endif +#if !(PWM14 < 0) + if (pwm_counter > esp8266_pwm[14]) + { + mcu_clear_output(PWM14); + } +#endif +#if !(PWM15 < 0) + if (pwm_counter > esp8266_pwm[15]) + { + mcu_clear_output(PWM15); + } +#endif + } + else + { +#if !(PWM0 < 0) + mcu_set_output(PWM0); +#endif +#if !(PWM1 < 0) + mcu_set_output(PWM1); +#endif +#if !(PWM2 < 0) + mcu_set_output(PWM2); +#endif +#if !(PWM3 < 0) + mcu_set_output(PWM3); +#endif +#if !(PWM4 < 0) + mcu_set_output(PWM4); +#endif +#if !(PWM5 < 0) + mcu_set_output(PWM5); +#endif +#if !(PWM6 < 0) + mcu_set_output(PWM6); +#endif +#if !(PWM7 < 0) + mcu_set_output(PWM7); +#endif +#if !(PWM8 < 0) + mcu_set_output(PWM8); +#endif +#if !(PWM9 < 0) + mcu_set_output(PWM9); +#endif +#if !(PWM10 < 0) + mcu_set_output(PWM10); +#endif +#if !(PWM11 < 0) + mcu_set_output(PWM11); +#endif +#if !(PWM12 < 0) + mcu_set_output(PWM12); +#endif +#if !(PWM13 < 0) + mcu_set_output(PWM13); +#endif +#if !(PWM14 < 0) + mcu_set_output(PWM14); +#endif +#if !(PWM15 < 0) + mcu_set_output(PWM15); +#endif + } + + mcu_rtc_cb(mcu_runtime_ms); +} + +IRAM_ATTR void mcu_itp_isr(void) +{ + mcu_disable_global_isr(); + static bool resetstep = false; + if (!resetstep) + mcu_step_cb(); + else + mcu_step_reset_cb(); + resetstep = !resetstep; + mcu_enable_global_isr(); +} + +// static void mcu_uart_isr(void *arg) +// { +// /*ATTENTION:*/ +// /*IN NON-OS VERSION SDK, DO NOT USE "ICACHE_FLASH_ATTR" FUNCTIONS IN THE WHOLE HANDLER PROCESS*/ +// /*ALL THE FUNCTIONS CALLED IN INTERRUPT HANDLER MUST BE DECLARED IN RAM */ +// /*IF NOT , POST AN EVENT AND PROCESS IN SYSTEM TASK */ +// if ((READ_PERI_REG(UART_INT_ST(0)) & UART_FRM_ERR_INT_ST)) +// { +// WRITE_PERI_REG(UART_INT_CLR(0), UART_FRM_ERR_INT_CLR); +// } +// else if ((READ_PERI_REG(UART_INT_ST(0)) & (UART_RXFIFO_FULL_INT_ST | UART_RXFIFO_TOUT_INT_ST))) +// { +// // disable ISR +// CLEAR_PERI_REG_MASK(UART_INT_ENA(0), UART_RXFIFO_FULL_INT_ENA | UART_RXFIFO_TOUT_INT_ENA); +// WRITE_PERI_REG(UART_INT_CLR(0), (READ_PERI_REG(UART_INT_ST(0)) & (UART_RXFIFO_FULL_INT_ST | UART_RXFIFO_TOUT_INT_ST))); +// uint8_t fifo_len = (READ_PERI_REG(UART_STATUS(0)) >> UART_RXFIFO_CNT_S) & UART_RXFIFO_CNT; +// unsigned char c = 0; + +// for (uint8_t i = 0; i < fifo_len; i++) +// { +// c = READ_PERI_REG(UART_FIFO(0)) & 0xFF; +// mcu_com_rx_cb(c); +// } + +// WRITE_PERI_REG(UART_INT_CLR(0), UART_RXFIFO_FULL_INT_CLR | UART_RXFIFO_TOUT_INT_CLR); +// // reenable ISR +// SET_PERI_REG_MASK(UART_INT_ENA(0), UART_RXFIFO_FULL_INT_ENA | UART_RXFIFO_TOUT_INT_ENA); +// } +// else if (UART_TXFIFO_EMPTY_INT_ST == (READ_PERI_REG(UART_INT_ST(0)) & UART_TXFIFO_EMPTY_INT_ST)) +// { +// /* to output uart data from uart buffer directly in empty interrupt handler*/ +// /*instead of processing in system event, in order not to wait for current task/function to quit */ +// /*ATTENTION:*/ +// /*IN NON-OS VERSION SDK, DO NOT USE "ICACHE_FLASH_ATTR" FUNCTIONS IN THE WHOLE HANDLER PROCESS*/ +// /*ALL THE FUNCTIONS CALLED IN INTERRUPT HANDLER MUST BE DECLARED IN RAM */ +// CLEAR_PERI_REG_MASK(UART_INT_ENA(0), UART_TXFIFO_EMPTY_INT_ENA); +// mcu_com_tx_cb(); +// // system_os_post(uart_recvTaskPrio, 1, 0); +// WRITE_PERI_REG(UART_INT_CLR(0), UART_TXFIFO_EMPTY_INT_CLR); +// } +// else if (UART_RXFIFO_OVF_INT_ST == (READ_PERI_REG(UART_INT_ST(0)) & UART_RXFIFO_OVF_INT_ST)) +// { +// WRITE_PERI_REG(UART_INT_CLR(0), UART_RXFIFO_OVF_INT_CLR); +// } +// } + +void mcu_usart_init(void) +{ +#if (INTERFACE == INTERFACE_USART) + esp8266_uart_init(BAUDRATE); +#elif (INTERFACE == INTERFACE_WIFI) + esp8266_wifi_init(); +#endif +} /** * initializes the mcu * this function needs to: @@ -99,6 +354,12 @@ void mcu_init(void) #if DIR5 >= 0 mcu_config_output(DIR5); #endif +#if DIR6 >= 0 + mcu_config_output(DIR6); +#endif +#if DIR7 >= 0 + mcu_config_output(DIR7); +#endif #if STEP0_EN >= 0 mcu_config_output(STEP0_EN); #endif @@ -117,6 +378,12 @@ void mcu_init(void) #if STEP5_EN >= 0 mcu_config_output(STEP5_EN); #endif +#if STEP6_EN >= 0 + mcu_config_output(STEP6_EN); +#endif +#if STEP7_EN >= 0 + mcu_config_output(STEP7_EN); +#endif #if PWM0 >= 0 mcu_config_pwm(PWM0); #endif @@ -165,6 +432,24 @@ void mcu_init(void) #if PWM15 >= 0 mcu_config_pwm(PWM15); #endif +#if SERVO0 >= 0 + mcu_config_output(SERVO0); +#endif +#if SERVO1 >= 0 + mcu_config_output(SERVO1); +#endif +#if SERVO2 >= 0 + mcu_config_output(SERVO2); +#endif +#if SERVO3 >= 0 + mcu_config_output(SERVO3); +#endif +#if SERVO4 >= 0 + mcu_config_output(SERVO4); +#endif +#if SERVO5 >= 0 + mcu_config_output(SERVO5); +#endif #if DOUT0 >= 0 mcu_config_output(DOUT0); #endif @@ -213,6 +498,54 @@ void mcu_init(void) #if DOUT15 >= 0 mcu_config_output(DOUT15); #endif +#if DOUT16 >= 0 + mcu_config_output(DOUT16); +#endif +#if DOUT17 >= 0 + mcu_config_output(DOUT17); +#endif +#if DOUT18 >= 0 + mcu_config_output(DOUT18); +#endif +#if DOUT19 >= 0 + mcu_config_output(DOUT19); +#endif +#if DOUT20 >= 0 + mcu_config_output(DOUT20); +#endif +#if DOUT21 >= 0 + mcu_config_output(DOUT21); +#endif +#if DOUT22 >= 0 + mcu_config_output(DOUT22); +#endif +#if DOUT23 >= 0 + mcu_config_output(DOUT23); +#endif +#if DOUT24 >= 0 + mcu_config_output(DOUT24); +#endif +#if DOUT25 >= 0 + mcu_config_output(DOUT25); +#endif +#if DOUT26 >= 0 + mcu_config_output(DOUT26); +#endif +#if DOUT27 >= 0 + mcu_config_output(DOUT27); +#endif +#if DOUT28 >= 0 + mcu_config_output(DOUT28); +#endif +#if DOUT29 >= 0 + mcu_config_output(DOUT29); +#endif +#if DOUT30 >= 0 + mcu_config_output(DOUT30); +#endif +#if DOUT31 >= 0 + mcu_config_output(DOUT31); +#endif #if LIMIT_X >= 0 mcu_config_input(LIMIT_X); #ifdef LIMIT_X_PULLUP @@ -507,12 +840,145 @@ void mcu_init(void) mcu_config_pullup(DIN15); #endif #endif +#if DIN16 >= 0 + mcu_config_input(DIN16); +#ifdef DIN16_PULLUP + mcu_config_pullup(DIN16); +#endif +#endif +#if DIN17 >= 0 + mcu_config_input(DIN17); +#ifdef DIN17_PULLUP + mcu_config_pullup(DIN17); +#endif +#endif +#if DIN18 >= 0 + mcu_config_input(DIN18); +#ifdef DIN18_PULLUP + mcu_config_pullup(DIN18); +#endif +#endif +#if DIN19 >= 0 + mcu_config_input(DIN19); +#ifdef DIN19_PULLUP + mcu_config_pullup(DIN19); +#endif +#endif +#if DIN20 >= 0 + mcu_config_input(DIN20); +#ifdef DIN20_PULLUP + mcu_config_pullup(DIN20); +#endif +#endif +#if DIN21 >= 0 + mcu_config_input(DIN21); +#ifdef DIN21_PULLUP + mcu_config_pullup(DIN21); +#endif +#endif +#if DIN22 >= 0 + mcu_config_input(DIN22); +#ifdef DIN22_PULLUP + mcu_config_pullup(DIN22); +#endif +#endif +#if DIN23 >= 0 + mcu_config_input(DIN23); +#ifdef DIN23_PULLUP + mcu_config_pullup(DIN23); +#endif +#endif +#if DIN24 >= 0 + mcu_config_input(DIN24); +#ifdef DIN24_PULLUP + mcu_config_pullup(DIN24); +#endif +#endif +#if DIN25 >= 0 + mcu_config_input(DIN25); +#ifdef DIN25_PULLUP + mcu_config_pullup(DIN25); +#endif +#endif +#if DIN26 >= 0 + mcu_config_input(DIN26); +#ifdef DIN26_PULLUP + mcu_config_pullup(DIN26); +#endif +#endif +#if DIN27 >= 0 + mcu_config_input(DIN27); +#ifdef DIN27_PULLUP + mcu_config_pullup(DIN27); +#endif +#endif +#if DIN28 >= 0 + mcu_config_input(DIN28); +#ifdef DIN28_PULLUP + mcu_config_pullup(DIN28); +#endif +#endif +#if DIN29 >= 0 + mcu_config_input(DIN29); +#ifdef DIN29_PULLUP + mcu_config_pullup(DIN29); +#endif +#endif +#if DIN30 >= 0 + mcu_config_input(DIN30); +#ifdef DIN30_PULLUP + mcu_config_pullup(DIN30); +#endif +#endif +#if DIN31 >= 0 + mcu_config_input(DIN31); +#ifdef DIN31_PULLUP + mcu_config_pullup(DIN31); +#endif +#endif #if TX >= 0 mcu_config_output(TX); #endif #if RX >= 0 - mcu_config_output(RX); + mcu_config_input(RX); +#ifdef RX_PULLUP + mcu_config_pullup(RX); +#endif +#endif +#if USB_DM >= 0 + mcu_config_input(USB_DM); +#ifdef USB_DM_PULLUP + mcu_config_pullup(USB_DM); +#endif #endif +#if USB_DP >= 0 + mcu_config_input(USB_DP); +#ifdef USB_DP_PULLUP + mcu_config_pullup(USB_DP); +#endif +#endif +#if SPI_CLK >= 0 + mcu_config_output(SPI_CLK); +#endif +#if SPI_SDI >= 0 + mcu_config_input(SPI_SDI); +#ifdef SPI_SDI_PULLUP + mcu_config_pullup(SPI_SDI); +#endif +#endif +#if SPI_SDO >= 0 + mcu_config_output(SPI_SDO); +#endif + + tx_ptr = esp8266_tx_buffer; + mcu_usart_init(); + + // init rtc + os_timer_setfn(&esp8266_rtc_timer, (os_timer_func_t *)&mcu_rtc_isr, NULL); + os_timer_arm(&esp8266_rtc_timer, 1, true); + + // init timer1 + timer1_isr_init(); } /** @@ -520,7 +986,9 @@ void mcu_init(void) * can be defined either as a function or a macro call * */ #ifndef mcu_enable_probe_isr -void mcu_enable_probe_isr(void); +void mcu_enable_probe_isr(void) +{ +} #endif /** @@ -528,7 +996,9 @@ void mcu_enable_probe_isr(void); * can be defined either as a function or a macro call * */ #ifndef mcu_disable_probe_isr -void mcu_disable_probe_isr(void); +void mcu_disable_probe_isr(void) +{ +} #endif /** @@ -536,7 +1006,10 @@ void mcu_disable_probe_isr(void); * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel); +uint8_t mcu_get_analog(uint8_t channel) +{ + return 0; +} #endif /** @@ -544,7 +1017,9 @@ uint8_t mcu_get_analog(uint8_t channel); * can be defined either as a function or a macro call * */ #ifndef mcu_set_pwm -void mcu_set_pwm(uint8_t pwm, uint8_t value); +void mcu_set_pwm(uint8_t pwm, uint8_t value) +{ +} #endif /** @@ -552,21 +1027,30 @@ void mcu_set_pwm(uint8_t pwm, uint8_t value); * can be defined either as a function or a macro call * */ #ifndef mcu_get_pwm -uint8_t mcu_get_pwm(uint8_t pwm); +uint8_t mcu_get_pwm(uint8_t pwm) +{ + return 0; +} #endif /** * checks if the serial hardware of the MCU is ready do send the next char * */ #ifndef mcu_tx_ready -bool mcu_tx_ready(void); // Start async send +bool mcu_tx_ready(void) +{ + return esp8266_uart_tx_ready(); +} #endif /** * checks if the serial hardware of the MCU has a new char ready to be read * */ #ifndef mcu_rx_ready -bool mcu_rx_ready(void); // Stop async send +bool mcu_rx_ready(void) +{ + return esp8266_uart_rx_ready(); +} #endif /** @@ -574,7 +1058,36 @@ bool mcu_rx_ready(void); // Stop async send * can be defined either as a function or a macro call * */ #ifndef mcu_putc -void mcu_putc(char c); + +void mcu_putc(char c) +{ +#if !(LED < 0) + mcu_toggle_output(LED); +#endif +#if (INTERFACE == INTERFACE_USART) +#ifdef ENABLE_SYNC_TX + while (!mcu_tx_ready()) + ; +#endif + esp8266_uart_write(c); +#elif (INTERFACE == INTERFACE_WIFI) + if (c != 0) + { + *tx_ptr = c; + tx_ptr++; + tx_ptr = 0; + } + if (c == '\r' || c == 0) + { + *tx_ptr = c; + tx_ptr++; + tx_ptr = 0; + uint8_t len = strlen(esp8266_tx_buffer); + esp8266_wifi_write(esp8266_tx_buffer, len); + tx_ptr = esp8266_tx_buffer; + } +#endif +} #endif /** @@ -582,7 +1095,21 @@ void mcu_putc(char c); * can be defined either as a function or a macro call * */ #ifndef mcu_getc -char mcu_getc(void); +char mcu_getc(void) +{ +#if !(LED < 0) + mcu_toggle_output(LED); +#endif +#if (INTERFACE == INTERFACE_USART) +#ifdef ENABLE_SYNC_RX + while (!mcu_rx_ready()) + ; +#endif + return esp8266_uart_read(); +#elif (INTERFACE == INTERFACE_WIFI) +#endif + return 0; +} #endif // ISR @@ -591,7 +1118,11 @@ char mcu_getc(void); * can be defined either as a function or a macro call * */ #ifndef mcu_enable_global_isr -void mcu_enable_global_isr(void); +void mcu_enable_global_isr(void) +{ + //ets_intr_unlock(); + esp8266_global_isr_enabled = true; +} #endif /** @@ -599,7 +1130,11 @@ void mcu_enable_global_isr(void); * can be defined either as a function or a macro call * */ #ifndef mcu_disable_global_isr -void mcu_disable_global_isr(void); +void mcu_disable_global_isr(void) +{ + esp8266_global_isr_enabled = false; + //ets_intr_lock(); +} #endif /** @@ -607,35 +1142,71 @@ void mcu_disable_global_isr(void); * can be defined either as a function or a macro call * */ #ifndef mcu_get_global_isr -bool mcu_get_global_isr(void); +bool mcu_get_global_isr(void) +{ + return esp8266_global_isr_enabled; +} #endif // Step interpolator /** * convert step rate to clock cycles * */ -void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller); +void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) +{ + // up and down counter (generates half the step rate at each event) + uint32_t totalticks = (uint32_t)((float)(F_CPU >> 5) / frequency); + while (totalticks > 0xFFFF) + { + totalticks = 0xFFFF; + } + + *ticks = (uint16_t)totalticks; +} /** * starts the timer interrupt that generates the step pulses for the interpolator * */ -void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller); +void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) +{ + timer1_attachInterrupt(mcu_itp_isr); + timer1_enable(TIM_DIV16, TIM_EDGE, TIM_LOOP); + timer1_write(ticks); +} /** * changes the step rate of the timer interrupt that generates the step pulses for the interpolator * */ -void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller); +void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller) +{ + timer1_write(ticks); +} /** * stops the timer interrupt that generates the step pulses for the interpolator * */ -void mcu_stop_itp_isr(void); +void mcu_stop_itp_isr(void) +{ + timer1_disable(); + timer1_detachInterrupt(); +} /** * gets the MCU running time in milliseconds. * the time counting is controled by the internal RTC * */ -uint32_t mcu_millis(); +uint32_t mcu_millis() +{ + return mcu_runtime_ms; +} + +#ifndef mcu_delay_us + void mcu_delay_us(uint8_t delay) + { + uint32_t time = system_get_time() + delay; + while(time>system_get_time()); + } +#endif /** * runs all internal tasks of the MCU. @@ -644,22 +1215,48 @@ uint32_t mcu_millis(); * - if ENABLE_SYNC_RX is enabled check if there are any chars in the rx transmitter (or the tinyUSB buffer) and read them to the serial_rx_isr * - if ENABLE_SYNC_TX is enabled check if serial_tx_empty is false and run serial_tx_isr * */ -void mcu_dotasks(void); +void mcu_dotasks(void) +{ + // reset WDT + system_soft_wdt_feed(); + +#if (INTERFACE == INTERFACE_USART) +#ifdef ENABLE_SYNC_TX + esp8266_uart_flush(); +#endif +#ifdef ENABLE_SYNC_RX + while (mcu_rx_ready()) + { + unsigned char c = mcu_getc(); + mcu_com_rx_cb(c); + } +#endif +#elif (INTERFACE == INTERFACE_WIFI) + esp8266_wifi_read(mcu_com_rx_cb); +#endif +} // Non volatile memory /** * gets a byte at the given EEPROM (or other non volatile memory) address of the MCU. * */ -uint8_t mcu_eeprom_getc(uint16_t address); +uint8_t mcu_eeprom_getc(uint16_t address) +{ + return 0; +} /** * sets a byte at the given EEPROM (or other non volatile memory) address of the MCU. * */ -void mcu_eeprom_putc(uint16_t address, uint8_t value); +void mcu_eeprom_putc(uint16_t address, uint8_t value) +{ +} /** * flushes all recorded registers into the eeprom. * */ -void mcu_eeprom_flush(void); +void mcu_eeprom_flush(void) +{ +} #endif diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 86885d126..e6ec2fb0b 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -24,6 +24,8 @@ extern "C" { #endif +#include + /* Generates all the interface definitions. This creates a middle HAL layer between the board IO pins and the AVR funtionalities @@ -33,7 +35,7 @@ extern "C" */ /* - AVR Defaults + ESP8266 Defaults */ // defines the frequency of the mcu #ifndef F_CPU @@ -44,17 +46,17 @@ extern "C" #define F_STEP_MAX 100000 #endif #ifndef F_STEP_MIN -#define F_STEP_MIN 4 +#define F_STEP_MIN 1 #endif // defines special mcu to access flash strings and arrays -#define __rom__ PROGMEM -#define __romstr__ PSTR -#define rom_strptr pgm_read_byte -#define rom_strcpy strcpy_P -#define rom_strncpy strncpy_P -#define rom_memcpy memcpy_P -#define rom_read_byte pgm_read_byte +#define __rom__ +#define __romstr__ +#define rom_strptr * +#define rom_strcpy strcpy +#define rom_strncpy strncpy +#define rom_memcpy memcpy +#define rom_read_byte * #define __SIZEOF_FLOAT__ 4 @@ -63,505 +65,908 @@ extern "C" // overrides utils.h definition to implement this method with or without fast math option enabled #define fast_int_mul10(x) ((((x) << 2) + (x)) << 1) -#if (defined(STEP0_BIT)) -#define DIO0 0 +// PINNAMES for ESP8266 +#define PERIPHS_IO_MUX_GPIO0 (PERIPHS_IO_MUX + 0x34) +#define PERIPHS_IO_MUX_GPIO1 (PERIPHS_IO_MUX + 0x18) +#define PERIPHS_IO_MUX_GPIO2 (PERIPHS_IO_MUX + 0x38) +#define PERIPHS_IO_MUX_GPIO3 (PERIPHS_IO_MUX + 0x14) +#define PERIPHS_IO_MUX_GPIO4 (PERIPHS_IO_MUX + 0x3C) +#define PERIPHS_IO_MUX_GPIO5 (PERIPHS_IO_MUX + 0x40) +#define PERIPHS_IO_MUX_GPIO6 (PERIPHS_IO_MUX + 0x1c) +#define PERIPHS_IO_MUX_GPIO7 (PERIPHS_IO_MUX + 0x20) +#define PERIPHS_IO_MUX_GPIO8 (PERIPHS_IO_MUX + 0x24) +#define PERIPHS_IO_MUX_GPIO9 (PERIPHS_IO_MUX + 0x28) +#define PERIPHS_IO_MUX_GPIO10 (PERIPHS_IO_MUX + 0x2c) +#define PERIPHS_IO_MUX_GPIO11 (PERIPHS_IO_MUX + 0x30) +#define PERIPHS_IO_MUX_GPIO12 (PERIPHS_IO_MUX + 0x04) +#define PERIPHS_IO_MUX_GPIO13 (PERIPHS_IO_MUX + 0x08) +#define PERIPHS_IO_MUX_GPIO14 (PERIPHS_IO_MUX + 0x0C) +#define PERIPHS_IO_MUX_GPIO15 (PERIPHS_IO_MUX + 0x10) + +#define __gpioreg__(X) (__helper__(PERIPHS_IO_MUX_GPIO, X, )) + +// IO pins +#if (defined(STEP0_PORT) && defined(STEP0_BIT)) #define STEP0 0 -#define DIO0_BIT (STEP0_BIT) +#define DIO0 0 +#define DIO0_PORT STEP0_PORT +#define DIO0_BIT STEP0_BIT #endif -#if (defined(STEP1_BIT)) -#define DIO1 1 +#if (defined(STEP1_PORT) && defined(STEP1_BIT)) #define STEP1 1 -#define DIO1_BIT (STEP1_BIT) +#define DIO1 1 +#define DIO1_PORT STEP1_PORT +#define DIO1_BIT STEP1_BIT #endif -#if (defined(STEP2_BIT)) -#define DIO2 2 +#if (defined(STEP2_PORT) && defined(STEP2_BIT)) #define STEP2 2 -#define DIO2_BIT (STEP2_BIT) +#define DIO2 2 +#define DIO2_PORT STEP2_PORT +#define DIO2_BIT STEP2_BIT #endif -#if (defined(STEP3_BIT)) -#define DIO3 3 +#if (defined(STEP3_PORT) && defined(STEP3_BIT)) #define STEP3 3 -#define DIO3_BIT (STEP3_BIT) +#define DIO3 3 +#define DIO3_PORT STEP3_PORT +#define DIO3_BIT STEP3_BIT #endif -#if (defined(STEP4_BIT)) -#define DIO4 4 +#if (defined(STEP4_PORT) && defined(STEP4_BIT)) #define STEP4 4 -#define DIO4_BIT (STEP4_BIT) +#define DIO4 4 +#define DIO4_PORT STEP4_PORT +#define DIO4_BIT STEP4_BIT #endif -#if (defined(STEP5_BIT)) -#define DIO5 5 +#if (defined(STEP5_PORT) && defined(STEP5_BIT)) #define STEP5 5 -#define DIO5_BIT (STEP5_BIT) +#define DIO5 5 +#define DIO5_PORT STEP5_PORT +#define DIO5_BIT STEP5_BIT #endif -#if (defined(STEP6_BIT)) -#define DIO6 6 +#if (defined(STEP6_PORT) && defined(STEP6_BIT)) #define STEP6 6 -#define DIO6_BIT (STEP6_BIT) +#define DIO6 6 +#define DIO6_PORT STEP6_PORT +#define DIO6_BIT STEP6_BIT #endif -#if (defined(STEP7_BIT)) -#define DIO7 7 +#if (defined(STEP7_PORT) && defined(STEP7_BIT)) #define STEP7 7 -#define DIO7_BIT (STEP7_BIT) +#define DIO7 7 +#define DIO7_PORT STEP7_PORT +#define DIO7_BIT STEP7_BIT #endif -#if (defined(DIR0_BIT)) -#define DIO8 8 +#if (defined(DIR0_PORT) && defined(DIR0_BIT)) #define DIR0 8 -#define DIO8_BIT (DIR0_BIT) +#define DIO8 8 +#define DIO8_PORT DIR0_PORT +#define DIO8_BIT DIR0_BIT #endif -#if (defined(DIR1_BIT)) -#define DIO9 9 +#if (defined(DIR1_PORT) && defined(DIR1_BIT)) #define DIR1 9 -#define DIO9_BIT (DIR1_BIT) +#define DIO9 9 +#define DIO9_PORT DIR1_PORT +#define DIO9_BIT DIR1_BIT #endif -#if (defined(DIR2_BIT)) -#define DIO10 10 +#if (defined(DIR2_PORT) && defined(DIR2_BIT)) #define DIR2 10 -#define DIO10_BIT (DIR2_BIT) +#define DIO10 10 +#define DIO10_PORT DIR2_PORT +#define DIO10_BIT DIR2_BIT #endif -#if (defined(DIR3_BIT)) -#define DIO11 11 +#if (defined(DIR3_PORT) && defined(DIR3_BIT)) #define DIR3 11 -#define DIO11_BIT (DIR3_BIT) +#define DIO11 11 +#define DIO11_PORT DIR3_PORT +#define DIO11_BIT DIR3_BIT #endif -#if (defined(DIR4_BIT)) -#define DIO12 12 +#if (defined(DIR4_PORT) && defined(DIR4_BIT)) #define DIR4 12 -#define DIO12_BIT (DIR4_BIT) +#define DIO12 12 +#define DIO12_PORT DIR4_PORT +#define DIO12_BIT DIR4_BIT #endif -#if (defined(DIR5_BIT)) -#define DIO13 13 +#if (defined(DIR5_PORT) && defined(DIR5_BIT)) #define DIR5 13 -#define DIO13_BIT (DIR5_BIT) +#define DIO13 13 +#define DIO13_PORT DIR5_PORT +#define DIO13_BIT DIR5_BIT #endif -#if (defined(STEP0_EN_BIT)) +#if (defined(DIR6_PORT) && defined(DIR6_BIT)) +#define DIR6 14 #define DIO14 14 -#define STEP0_EN 14 -#define DIO14_BIT (STEP0_EN_BIT) +#define DIO14_PORT DIR6_PORT +#define DIO14_BIT DIR6_BIT #endif -#if (defined(STEP1_EN_BIT)) +#if (defined(DIR7_PORT) && defined(DIR7_BIT)) +#define DIR7 15 #define DIO15 15 -#define STEP1_EN 15 -#define DIO15_BIT (STEP1_EN_BIT) +#define DIO15_PORT DIR7_PORT +#define DIO15_BIT DIR7_BIT #endif -#if (defined(STEP2_EN_BIT)) +#if (defined(STEP0_EN_PORT) && defined(STEP0_EN_BIT)) +#define STEP0_EN 16 #define DIO16 16 -#define STEP2_EN 16 -#define DIO16_BIT (STEP2_EN_BIT) +#define DIO16_PORT STEP0_EN_PORT +#define DIO16_BIT STEP0_EN_BIT #endif -#if (defined(STEP3_EN_BIT)) +#if (defined(STEP1_EN_PORT) && defined(STEP1_EN_BIT)) +#define STEP1_EN 17 #define DIO17 17 -#define STEP3_EN 17 -#define DIO17_BIT (STEP3_EN_BIT) +#define DIO17_PORT STEP1_EN_PORT +#define DIO17_BIT STEP1_EN_BIT #endif -#if (defined(STEP4_EN_BIT)) +#if (defined(STEP2_EN_PORT) && defined(STEP2_EN_BIT)) +#define STEP2_EN 18 #define DIO18 18 -#define STEP4_EN 18 -#define DIO18_BIT (STEP4_EN_BIT) +#define DIO18_PORT STEP2_EN_PORT +#define DIO18_BIT STEP2_EN_BIT #endif -#if (defined(STEP5_EN_BIT)) +#if (defined(STEP3_EN_PORT) && defined(STEP3_EN_BIT)) +#define STEP3_EN 19 #define DIO19 19 -#define STEP5_EN 19 -#define DIO19_BIT (STEP5_EN_BIT) +#define DIO19_PORT STEP3_EN_PORT +#define DIO19_BIT STEP3_EN_BIT #endif -#if (defined(PWM0_BIT)) +#if (defined(STEP4_EN_PORT) && defined(STEP4_EN_BIT)) +#define STEP4_EN 20 #define DIO20 20 -#define PWM0 20 -#define DIO20_BIT (PWM0_BIT) +#define DIO20_PORT STEP4_EN_PORT +#define DIO20_BIT STEP4_EN_BIT #endif -#if (defined(PWM1_BIT)) +#if (defined(STEP5_EN_PORT) && defined(STEP5_EN_BIT)) +#define STEP5_EN 21 #define DIO21 21 -#define PWM1 21 -#define DIO21_BIT (PWM1_BIT) +#define DIO21_PORT STEP5_EN_PORT +#define DIO21_BIT STEP5_EN_BIT #endif -#if (defined(PWM2_BIT)) +#if (defined(STEP6_EN_PORT) && defined(STEP6_EN_BIT)) +#define STEP6_EN 22 #define DIO22 22 -#define PWM2 22 -#define DIO22_BIT (PWM2_BIT) +#define DIO22_PORT STEP6_EN_PORT +#define DIO22_BIT STEP6_EN_BIT #endif -#if (defined(PWM3_BIT)) +#if (defined(STEP7_EN_PORT) && defined(STEP7_EN_BIT)) +#define STEP7_EN 23 #define DIO23 23 -#define PWM3 23 -#define DIO23_BIT (PWM3_BIT) +#define DIO23_PORT STEP7_EN_PORT +#define DIO23_BIT STEP7_EN_BIT #endif -#if (defined(PWM4_BIT)) +#if (defined(PWM0_PORT) && defined(PWM0_BIT)) +#define PWM0 24 #define DIO24 24 -#define PWM4 24 -#define DIO24_BIT (PWM4_BIT) +#define DIO24_PORT PWM0_PORT +#define DIO24_BIT PWM0_BIT #endif -#if (defined(PWM5_BIT)) +#if (defined(PWM1_PORT) && defined(PWM1_BIT)) +#define PWM1 25 #define DIO25 25 -#define PWM5 25 -#define DIO25_BIT (PWM5_BIT) +#define DIO25_PORT PWM1_PORT +#define DIO25_BIT PWM1_BIT #endif -#if (defined(PWM6_BIT)) +#if (defined(PWM2_PORT) && defined(PWM2_BIT)) +#define PWM2 26 #define DIO26 26 -#define PWM6 26 -#define DIO26_BIT (PWM6_BIT) +#define DIO26_PORT PWM2_PORT +#define DIO26_BIT PWM2_BIT #endif -#if (defined(PWM7_BIT)) +#if (defined(PWM3_PORT) && defined(PWM3_BIT)) +#define PWM3 27 #define DIO27 27 -#define PWM7 27 -#define DIO27_BIT (PWM7_BIT) +#define DIO27_PORT PWM3_PORT +#define DIO27_BIT PWM3_BIT #endif -#if (defined(PWM8_BIT)) +#if (defined(PWM4_PORT) && defined(PWM4_BIT)) +#define PWM4 28 #define DIO28 28 -#define PWM8 28 -#define DIO28_BIT (PWM8_BIT) +#define DIO28_PORT PWM4_PORT +#define DIO28_BIT PWM4_BIT #endif -#if (defined(PWM9_BIT)) +#if (defined(PWM5_PORT) && defined(PWM5_BIT)) +#define PWM5 29 #define DIO29 29 -#define PWM9 29 -#define DIO29_BIT (PWM9_BIT) +#define DIO29_PORT PWM5_PORT +#define DIO29_BIT PWM5_BIT #endif -#if (defined(PWM10_BIT)) +#if (defined(PWM6_PORT) && defined(PWM6_BIT)) +#define PWM6 30 #define DIO30 30 -#define PWM10 30 -#define DIO30_BIT (PWM10_BIT) +#define DIO30_PORT PWM6_PORT +#define DIO30_BIT PWM6_BIT #endif -#if (defined(PWM11_BIT)) +#if (defined(PWM7_PORT) && defined(PWM7_BIT)) +#define PWM7 31 #define DIO31 31 -#define PWM11 31 -#define DIO31_BIT (PWM11_BIT) +#define DIO31_PORT PWM7_PORT +#define DIO31_BIT PWM7_BIT #endif -#if (defined(PWM12_BIT)) +#if (defined(PWM8_PORT) && defined(PWM8_BIT)) +#define PWM8 32 #define DIO32 32 -#define PWM12 32 -#define DIO32_BIT (PWM12_BIT) +#define DIO32_PORT PWM8_PORT +#define DIO32_BIT PWM8_BIT #endif -#if (defined(PWM13_BIT)) +#if (defined(PWM9_PORT) && defined(PWM9_BIT)) +#define PWM9 33 #define DIO33 33 -#define PWM13 33 -#define DIO33_BIT (PWM13_BIT) +#define DIO33_PORT PWM9_PORT +#define DIO33_BIT PWM9_BIT #endif -#if (defined(PWM14_BIT)) +#if (defined(PWM10_PORT) && defined(PWM10_BIT)) +#define PWM10 34 #define DIO34 34 -#define PWM14 34 -#define DIO34_BIT (PWM14_BIT) +#define DIO34_PORT PWM10_PORT +#define DIO34_BIT PWM10_BIT #endif -#if (defined(PWM15_BIT)) +#if (defined(PWM11_PORT) && defined(PWM11_BIT)) +#define PWM11 35 #define DIO35 35 -#define PWM15 35 -#define DIO35_BIT (PWM15_BIT) +#define DIO35_PORT PWM11_PORT +#define DIO35_BIT PWM11_BIT #endif -#if (defined(DOUT0_BIT)) +#if (defined(PWM12_PORT) && defined(PWM12_BIT)) +#define PWM12 36 #define DIO36 36 -#define DOUT0 36 -#define DIO36_BIT (DOUT0_BIT) +#define DIO36_PORT PWM12_PORT +#define DIO36_BIT PWM12_BIT #endif -#if (defined(DOUT1_BIT)) +#if (defined(PWM13_PORT) && defined(PWM13_BIT)) +#define PWM13 37 #define DIO37 37 -#define DOUT1 37 -#define DIO37_BIT (DOUT1_BIT) +#define DIO37_PORT PWM13_PORT +#define DIO37_BIT PWM13_BIT #endif -#if (defined(DOUT2_BIT)) +#if (defined(PWM14_PORT) && defined(PWM14_BIT)) +#define PWM14 38 #define DIO38 38 -#define DOUT2 38 -#define DIO38_BIT (DOUT2_BIT) +#define DIO38_PORT PWM14_PORT +#define DIO38_BIT PWM14_BIT #endif -#if (defined(DOUT3_BIT)) +#if (defined(PWM15_PORT) && defined(PWM15_BIT)) +#define PWM15 39 #define DIO39 39 -#define DOUT3 39 -#define DIO39_BIT (DOUT3_BIT) +#define DIO39_PORT PWM15_PORT +#define DIO39_BIT PWM15_BIT #endif -#if (defined(DOUT4_BIT)) +#if (defined(SERVO0_PORT) && defined(SERVO0_BIT)) +#define SERVO0 40 #define DIO40 40 -#define DOUT4 40 -#define DIO40_BIT (DOUT4_BIT) +#define DIO40_PORT SERVO0_PORT +#define DIO40_BIT SERVO0_BIT #endif -#if (defined(DOUT5_BIT)) +#if (defined(SERVO1_PORT) && defined(SERVO1_BIT)) +#define SERVO1 41 #define DIO41 41 -#define DOUT5 41 -#define DIO41_BIT (DOUT5_BIT) +#define DIO41_PORT SERVO1_PORT +#define DIO41_BIT SERVO1_BIT #endif -#if (defined(DOUT6_BIT)) +#if (defined(SERVO2_PORT) && defined(SERVO2_BIT)) +#define SERVO2 42 #define DIO42 42 -#define DOUT6 42 -#define DIO42_BIT (DOUT6_BIT) +#define DIO42_PORT SERVO2_PORT +#define DIO42_BIT SERVO2_BIT #endif -#if (defined(DOUT7_BIT)) +#if (defined(SERVO3_PORT) && defined(SERVO3_BIT)) +#define SERVO3 43 #define DIO43 43 -#define DOUT7 43 -#define DIO43_BIT (DOUT7_BIT) +#define DIO43_PORT SERVO3_PORT +#define DIO43_BIT SERVO3_BIT #endif -#if (defined(DOUT8_BIT)) +#if (defined(SERVO4_PORT) && defined(SERVO4_BIT)) +#define SERVO4 44 #define DIO44 44 -#define DOUT8 44 -#define DIO44_BIT (DOUT8_BIT) +#define DIO44_PORT SERVO4_PORT +#define DIO44_BIT SERVO4_BIT #endif -#if (defined(DOUT9_BIT)) +#if (defined(SERVO5_PORT) && defined(SERVO5_BIT)) +#define SERVO5 45 #define DIO45 45 -#define DOUT9 45 -#define DIO45_BIT (DOUT9_BIT) +#define DIO45_PORT SERVO5_PORT +#define DIO45_BIT SERVO5_BIT #endif -#if (defined(DOUT10_BIT)) +#if (defined(DOUT0_PORT) && defined(DOUT0_BIT)) +#define DOUT0 46 #define DIO46 46 -#define DOUT10 46 -#define DIO46_BIT (DOUT10_BIT) +#define DIO46_PORT DOUT0_PORT +#define DIO46_BIT DOUT0_BIT #endif -#if (defined(DOUT11_BIT)) +#if (defined(DOUT1_PORT) && defined(DOUT1_BIT)) +#define DOUT1 47 #define DIO47 47 -#define DOUT11 47 -#define DIO47_BIT (DOUT11_BIT) +#define DIO47_PORT DOUT1_PORT +#define DIO47_BIT DOUT1_BIT #endif -#if (defined(DOUT12_BIT)) +#if (defined(DOUT2_PORT) && defined(DOUT2_BIT)) +#define DOUT2 48 #define DIO48 48 -#define DOUT12 48 -#define DIO48_BIT (DOUT12_BIT) +#define DIO48_PORT DOUT2_PORT +#define DIO48_BIT DOUT2_BIT #endif -#if (defined(DOUT13_BIT)) +#if (defined(DOUT3_PORT) && defined(DOUT3_BIT)) +#define DOUT3 49 #define DIO49 49 -#define DOUT13 49 -#define DIO49_BIT (DOUT13_BIT) +#define DIO49_PORT DOUT3_PORT +#define DIO49_BIT DOUT3_BIT #endif -#if (defined(DOUT14_BIT)) +#if (defined(DOUT4_PORT) && defined(DOUT4_BIT)) +#define DOUT4 50 #define DIO50 50 -#define DOUT14 50 -#define DIO50_BIT (DOUT14_BIT) +#define DIO50_PORT DOUT4_PORT +#define DIO50_BIT DOUT4_BIT #endif -#if (defined(DOUT15_BIT)) +#if (defined(DOUT5_PORT) && defined(DOUT5_BIT)) +#define DOUT5 51 #define DIO51 51 -#define DOUT15 51 -#define DIO51_BIT (DOUT15_BIT) +#define DIO51_PORT DOUT5_PORT +#define DIO51_BIT DOUT5_BIT #endif -#if (defined(LIMIT_X_BIT)) +#if (defined(DOUT6_PORT) && defined(DOUT6_BIT)) +#define DOUT6 52 #define DIO52 52 -#define LIMIT_X 52 -#define DIO52_BIT (LIMIT_X_BIT) +#define DIO52_PORT DOUT6_PORT +#define DIO52_BIT DOUT6_BIT #endif -#if (defined(LIMIT_Y_BIT)) +#if (defined(DOUT7_PORT) && defined(DOUT7_BIT)) +#define DOUT7 53 #define DIO53 53 -#define LIMIT_Y 53 -#define DIO53_BIT (LIMIT_Y_BIT) +#define DIO53_PORT DOUT7_PORT +#define DIO53_BIT DOUT7_BIT #endif -#if (defined(LIMIT_Z_BIT)) +#if (defined(DOUT8_PORT) && defined(DOUT8_BIT)) +#define DOUT8 54 #define DIO54 54 -#define LIMIT_Z 54 -#define DIO54_BIT (LIMIT_Z_BIT) +#define DIO54_PORT DOUT8_PORT +#define DIO54_BIT DOUT8_BIT #endif -#if (defined(LIMIT_X2_BIT)) +#if (defined(DOUT9_PORT) && defined(DOUT9_BIT)) +#define DOUT9 55 #define DIO55 55 -#define LIMIT_X2 55 -#define DIO55_BIT (LIMIT_X2_BIT) +#define DIO55_PORT DOUT9_PORT +#define DIO55_BIT DOUT9_BIT #endif -#if (defined(LIMIT_Y2_BIT)) +#if (defined(DOUT10_PORT) && defined(DOUT10_BIT)) +#define DOUT10 56 #define DIO56 56 -#define LIMIT_Y2 56 -#define DIO56_BIT (LIMIT_Y2_BIT) +#define DIO56_PORT DOUT10_PORT +#define DIO56_BIT DOUT10_BIT #endif -#if (defined(LIMIT_Z2_BIT)) +#if (defined(DOUT11_PORT) && defined(DOUT11_BIT)) +#define DOUT11 57 #define DIO57 57 -#define LIMIT_Z2 57 -#define DIO57_BIT (LIMIT_Z2_BIT) +#define DIO57_PORT DOUT11_PORT +#define DIO57_BIT DOUT11_BIT #endif -#if (defined(LIMIT_A_BIT)) +#if (defined(DOUT12_PORT) && defined(DOUT12_BIT)) +#define DOUT12 58 #define DIO58 58 -#define LIMIT_A 58 -#define DIO58_BIT (LIMIT_A_BIT) +#define DIO58_PORT DOUT12_PORT +#define DIO58_BIT DOUT12_BIT #endif -#if (defined(LIMIT_B_BIT)) +#if (defined(DOUT13_PORT) && defined(DOUT13_BIT)) +#define DOUT13 59 #define DIO59 59 -#define LIMIT_B 59 -#define DIO59_BIT (LIMIT_B_BIT) +#define DIO59_PORT DOUT13_PORT +#define DIO59_BIT DOUT13_BIT #endif -#if (defined(LIMIT_C_BIT)) +#if (defined(DOUT14_PORT) && defined(DOUT14_BIT)) +#define DOUT14 60 #define DIO60 60 -#define LIMIT_C 60 -#define DIO60_BIT (LIMIT_C_BIT) +#define DIO60_PORT DOUT14_PORT +#define DIO60_BIT DOUT14_BIT #endif -#if (defined(PROBE_BIT)) +#if (defined(DOUT15_PORT) && defined(DOUT15_BIT)) +#define DOUT15 61 #define DIO61 61 -#define PROBE 61 -#define DIO61_BIT (PROBE_BIT) +#define DIO61_PORT DOUT15_PORT +#define DIO61_BIT DOUT15_BIT #endif -#if (defined(ESTOP_BIT)) +#if (defined(DOUT16_PORT) && defined(DOUT16_BIT)) +#define DOUT16 62 #define DIO62 62 -#define ESTOP 62 -#define DIO62_BIT (ESTOP_BIT) +#define DIO62_PORT DOUT16_PORT +#define DIO62_BIT DOUT16_BIT #endif -#if (defined(SAFETY_DOOR_BIT)) +#if (defined(DOUT17_PORT) && defined(DOUT17_BIT)) +#define DOUT17 63 #define DIO63 63 -#define SAFETY_DOOR 63 -#define DIO63_BIT (SAFETY_DOOR_BIT) +#define DIO63_PORT DOUT17_PORT +#define DIO63_BIT DOUT17_BIT #endif -#if (defined(FHOLD_BIT)) +#if (defined(DOUT18_PORT) && defined(DOUT18_BIT)) +#define DOUT18 64 #define DIO64 64 -#define FHOLD 64 -#define DIO64_BIT (FHOLD_BIT) +#define DIO64_PORT DOUT18_PORT +#define DIO64_BIT DOUT18_BIT #endif -#if (defined(CS_RES_BIT)) +#if (defined(DOUT19_PORT) && defined(DOUT19_BIT)) +#define DOUT19 65 #define DIO65 65 -#define CS_RES 65 -#define DIO65_BIT (CS_RES_BIT) +#define DIO65_PORT DOUT19_PORT +#define DIO65_BIT DOUT19_BIT #endif -#if (defined(ANALOG0_BIT)) +#if (defined(DOUT20_PORT) && defined(DOUT20_BIT)) +#define DOUT20 66 #define DIO66 66 -#define ANALOG0 66 -#define DIO66_BIT (ANALOG0_BIT) +#define DIO66_PORT DOUT20_PORT +#define DIO66_BIT DOUT20_BIT #endif -#if (defined(ANALOG1_BIT)) +#if (defined(DOUT21_PORT) && defined(DOUT21_BIT)) +#define DOUT21 67 #define DIO67 67 -#define ANALOG1 67 -#define DIO67_BIT (ANALOG1_BIT) +#define DIO67_PORT DOUT21_PORT +#define DIO67_BIT DOUT21_BIT #endif -#if (defined(ANALOG2_BIT)) +#if (defined(DOUT22_PORT) && defined(DOUT22_BIT)) +#define DOUT22 68 #define DIO68 68 -#define ANALOG2 68 -#define DIO68_BIT (ANALOG2_BIT) +#define DIO68_PORT DOUT22_PORT +#define DIO68_BIT DOUT22_BIT #endif -#if (defined(ANALOG3_BIT)) +#if (defined(DOUT23_PORT) && defined(DOUT23_BIT)) +#define DOUT23 69 #define DIO69 69 -#define ANALOG3 69 -#define DIO69_BIT (ANALOG3_BIT) +#define DIO69_PORT DOUT23_PORT +#define DIO69_BIT DOUT23_BIT #endif -#if (defined(ANALOG4_BIT)) +#if (defined(DOUT24_PORT) && defined(DOUT24_BIT)) +#define DOUT24 70 #define DIO70 70 -#define ANALOG4 70 -#define DIO70_BIT (ANALOG4_BIT) +#define DIO70_PORT DOUT24_PORT +#define DIO70_BIT DOUT24_BIT #endif -#if (defined(ANALOG5_BIT)) +#if (defined(DOUT25_PORT) && defined(DOUT25_BIT)) +#define DOUT25 71 #define DIO71 71 -#define ANALOG5 71 -#define DIO71_BIT (ANALOG5_BIT) +#define DIO71_PORT DOUT25_PORT +#define DIO71_BIT DOUT25_BIT #endif -#if (defined(ANALOG6_BIT)) +#if (defined(DOUT26_PORT) && defined(DOUT26_BIT)) +#define DOUT26 72 #define DIO72 72 -#define ANALOG6 72 -#define DIO72_BIT (ANALOG6_BIT) +#define DIO72_PORT DOUT26_PORT +#define DIO72_BIT DOUT26_BIT #endif -#if (defined(ANALOG7_BIT)) +#if (defined(DOUT27_PORT) && defined(DOUT27_BIT)) +#define DOUT27 73 #define DIO73 73 -#define ANALOG7 73 -#define DIO73_BIT (ANALOG7_BIT) +#define DIO73_PORT DOUT27_PORT +#define DIO73_BIT DOUT27_BIT #endif -#if (defined(ANALOG8_BIT)) +#if (defined(DOUT28_PORT) && defined(DOUT28_BIT)) +#define DOUT28 74 #define DIO74 74 -#define ANALOG8 74 -#define DIO74_BIT (ANALOG8_BIT) +#define DIO74_PORT DOUT28_PORT +#define DIO74_BIT DOUT28_BIT #endif -#if (defined(ANALOG9_BIT)) +#if (defined(DOUT29_PORT) && defined(DOUT29_BIT)) +#define DOUT29 75 #define DIO75 75 -#define ANALOG9 75 -#define DIO75_BIT (ANALOG9_BIT) +#define DIO75_PORT DOUT29_PORT +#define DIO75_BIT DOUT29_BIT #endif -#if (defined(ANALOG10_BIT)) +#if (defined(DOUT30_PORT) && defined(DOUT30_BIT)) +#define DOUT30 76 #define DIO76 76 -#define ANALOG10 76 -#define DIO76_BIT (ANALOG10_BIT) +#define DIO76_PORT DOUT30_PORT +#define DIO76_BIT DOUT30_BIT #endif -#if (defined(ANALOG11_BIT)) +#if (defined(DOUT31_PORT) && defined(DOUT31_BIT)) +#define DOUT31 77 #define DIO77 77 -#define ANALOG11 77 -#define DIO77_BIT (ANALOG11_BIT) -#endif -#if (defined(ANALOG12_BIT)) -#define DIO78 78 -#define ANALOG12 78 -#define DIO78_BIT (ANALOG12_BIT) -#endif -#if (defined(ANALOG13_BIT)) -#define DIO79 79 -#define ANALOG13 79 -#define DIO79_BIT (ANALOG13_BIT) -#endif -#if (defined(ANALOG14_BIT)) -#define DIO80 80 -#define ANALOG14 80 -#define DIO80_BIT (ANALOG14_BIT) -#endif -#if (defined(ANALOG15_BIT)) -#define DIO81 81 -#define ANALOG15 81 -#define DIO81_BIT (ANALOG15_BIT) -#endif -#if (defined(DIN0_BIT)) -#define DIO82 82 -#define DIN0 82 -#define DIO82_BIT (DIN0_BIT) -#endif -#if (defined(DIN1_BIT)) -#define DIO83 83 -#define DIN1 83 -#define DIO83_BIT (DIN1_BIT) -#endif -#if (defined(DIN2_BIT)) -#define DIO84 84 -#define DIN2 84 -#define DIO84_BIT (DIN2_BIT) -#endif -#if (defined(DIN3_BIT)) -#define DIO85 85 -#define DIN3 85 -#define DIO85_BIT (DIN3_BIT) -#endif -#if (defined(DIN4_BIT)) -#define DIO86 86 -#define DIN4 86 -#define DIO86_BIT (DIN4_BIT) -#endif -#if (defined(DIN5_BIT)) -#define DIO87 87 -#define DIN5 87 -#define DIO87_BIT (DIN5_BIT) -#endif -#if (defined(DIN6_BIT)) -#define DIO88 88 -#define DIN6 88 -#define DIO88_BIT (DIN6_BIT) -#endif -#if (defined(DIN7_BIT)) -#define DIO89 89 -#define DIN7 89 -#define DIO89_BIT (DIN7_BIT) -#endif -#if (defined(DIN8_BIT)) -#define DIO90 90 -#define DIN8 90 -#define DIO90_BIT (DIN8_BIT) -#endif -#if (defined(DIN9_BIT)) -#define DIO91 91 -#define DIN9 91 -#define DIO91_BIT (DIN9_BIT) -#endif -#if (defined(DIN10_BIT)) -#define DIO92 92 -#define DIN10 92 -#define DIO92_BIT (DIN10_BIT) -#endif -#if (defined(DIN11_BIT)) -#define DIO93 93 -#define DIN11 93 -#define DIO93_BIT (DIN11_BIT) -#endif -#if (defined(DIN12_BIT)) -#define DIO94 94 -#define DIN12 94 -#define DIO94_BIT (DIN12_BIT) -#endif -#if (defined(DIN13_BIT)) -#define DIO95 95 -#define DIN13 95 -#define DIO95_BIT (DIN13_BIT) -#endif -#if (defined(DIN14_BIT)) -#define DIO96 96 -#define DIN14 96 -#define DIO96_BIT (DIN14_BIT) -#endif -#if (defined(DIN15_BIT)) -#define DIO97 97 -#define DIN15 97 -#define DIO97_BIT (DIN15_BIT) -#endif -#if (defined(TX_BIT)) -#define DIO98 98 -#define TX 98 -#define DIO98_BIT (TX_BIT) -#endif -#if (defined(RX_BIT)) -#define DIO99 99 -#define RX 99 -#define DIO99_BIT (RX_BIT) +#define DIO77_PORT DOUT31_PORT +#define DIO77_BIT DOUT31_BIT +#endif +#if (defined(LIMIT_X_PORT) && defined(LIMIT_X_BIT)) +#define LIMIT_X 100 +#define DIO100 100 +#define DIO100_PORT LIMIT_X_PORT +#define DIO100_BIT LIMIT_X_BIT +#endif +#if (defined(LIMIT_Y_PORT) && defined(LIMIT_Y_BIT)) +#define LIMIT_Y 101 +#define DIO101 101 +#define DIO101_PORT LIMIT_Y_PORT +#define DIO101_BIT LIMIT_Y_BIT +#endif +#if (defined(LIMIT_Z_PORT) && defined(LIMIT_Z_BIT)) +#define LIMIT_Z 102 +#define DIO102 102 +#define DIO102_PORT LIMIT_Z_PORT +#define DIO102_BIT LIMIT_Z_BIT +#endif +#if (defined(LIMIT_X2_PORT) && defined(LIMIT_X2_BIT)) +#define LIMIT_X2 103 +#define DIO103 103 +#define DIO103_PORT LIMIT_X2_PORT +#define DIO103_BIT LIMIT_X2_BIT +#endif +#if (defined(LIMIT_Y2_PORT) && defined(LIMIT_Y2_BIT)) +#define LIMIT_Y2 104 +#define DIO104 104 +#define DIO104_PORT LIMIT_Y2_PORT +#define DIO104_BIT LIMIT_Y2_BIT +#endif +#if (defined(LIMIT_Z2_PORT) && defined(LIMIT_Z2_BIT)) +#define LIMIT_Z2 105 +#define DIO105 105 +#define DIO105_PORT LIMIT_Z2_PORT +#define DIO105_BIT LIMIT_Z2_BIT +#endif +#if (defined(LIMIT_A_PORT) && defined(LIMIT_A_BIT)) +#define LIMIT_A 106 +#define DIO106 106 +#define DIO106_PORT LIMIT_A_PORT +#define DIO106_BIT LIMIT_A_BIT +#endif +#if (defined(LIMIT_B_PORT) && defined(LIMIT_B_BIT)) +#define LIMIT_B 107 +#define DIO107 107 +#define DIO107_PORT LIMIT_B_PORT +#define DIO107_BIT LIMIT_B_BIT +#endif +#if (defined(LIMIT_C_PORT) && defined(LIMIT_C_BIT)) +#define LIMIT_C 108 +#define DIO108 108 +#define DIO108_PORT LIMIT_C_PORT +#define DIO108_BIT LIMIT_C_BIT +#endif +#if (defined(PROBE_PORT) && defined(PROBE_BIT)) +#define PROBE 109 +#define DIO109 109 +#define DIO109_PORT PROBE_PORT +#define DIO109_BIT PROBE_BIT +#endif +#if (defined(ESTOP_PORT) && defined(ESTOP_BIT)) +#define ESTOP 110 +#define DIO110 110 +#define DIO110_PORT ESTOP_PORT +#define DIO110_BIT ESTOP_BIT +#endif +#if (defined(SAFETY_DOOR_PORT) && defined(SAFETY_DOOR_BIT)) +#define SAFETY_DOOR 111 +#define DIO111 111 +#define DIO111_PORT SAFETY_DOOR_PORT +#define DIO111_BIT SAFETY_DOOR_BIT +#endif +#if (defined(FHOLD_PORT) && defined(FHOLD_BIT)) +#define FHOLD 112 +#define DIO112 112 +#define DIO112_PORT FHOLD_PORT +#define DIO112_BIT FHOLD_BIT +#endif +#if (defined(CS_RES_PORT) && defined(CS_RES_BIT)) +#define CS_RES 113 +#define DIO113 113 +#define DIO113_PORT CS_RES_PORT +#define DIO113_BIT CS_RES_BIT +#endif +#if (defined(ANALOG0_PORT) && defined(ANALOG0_BIT)) +#define ANALOG0 114 +#define DIO114 114 +#define DIO114_PORT ANALOG0_PORT +#define DIO114_BIT ANALOG0_BIT +#endif +#if (defined(ANALOG1_PORT) && defined(ANALOG1_BIT)) +#define ANALOG1 115 +#define DIO115 115 +#define DIO115_PORT ANALOG1_PORT +#define DIO115_BIT ANALOG1_BIT +#endif +#if (defined(ANALOG2_PORT) && defined(ANALOG2_BIT)) +#define ANALOG2 116 +#define DIO116 116 +#define DIO116_PORT ANALOG2_PORT +#define DIO116_BIT ANALOG2_BIT +#endif +#if (defined(ANALOG3_PORT) && defined(ANALOG3_BIT)) +#define ANALOG3 117 +#define DIO117 117 +#define DIO117_PORT ANALOG3_PORT +#define DIO117_BIT ANALOG3_BIT +#endif +#if (defined(ANALOG4_PORT) && defined(ANALOG4_BIT)) +#define ANALOG4 118 +#define DIO118 118 +#define DIO118_PORT ANALOG4_PORT +#define DIO118_BIT ANALOG4_BIT +#endif +#if (defined(ANALOG5_PORT) && defined(ANALOG5_BIT)) +#define ANALOG5 119 +#define DIO119 119 +#define DIO119_PORT ANALOG5_PORT +#define DIO119_BIT ANALOG5_BIT +#endif +#if (defined(ANALOG6_PORT) && defined(ANALOG6_BIT)) +#define ANALOG6 120 +#define DIO120 120 +#define DIO120_PORT ANALOG6_PORT +#define DIO120_BIT ANALOG6_BIT +#endif +#if (defined(ANALOG7_PORT) && defined(ANALOG7_BIT)) +#define ANALOG7 121 +#define DIO121 121 +#define DIO121_PORT ANALOG7_PORT +#define DIO121_BIT ANALOG7_BIT +#endif +#if (defined(ANALOG8_PORT) && defined(ANALOG8_BIT)) +#define ANALOG8 122 +#define DIO122 122 +#define DIO122_PORT ANALOG8_PORT +#define DIO122_BIT ANALOG8_BIT +#endif +#if (defined(ANALOG9_PORT) && defined(ANALOG9_BIT)) +#define ANALOG9 123 +#define DIO123 123 +#define DIO123_PORT ANALOG9_PORT +#define DIO123_BIT ANALOG9_BIT +#endif +#if (defined(ANALOG10_PORT) && defined(ANALOG10_BIT)) +#define ANALOG10 124 +#define DIO124 124 +#define DIO124_PORT ANALOG10_PORT +#define DIO124_BIT ANALOG10_BIT +#endif +#if (defined(ANALOG11_PORT) && defined(ANALOG11_BIT)) +#define ANALOG11 125 +#define DIO125 125 +#define DIO125_PORT ANALOG11_PORT +#define DIO125_BIT ANALOG11_BIT +#endif +#if (defined(ANALOG12_PORT) && defined(ANALOG12_BIT)) +#define ANALOG12 126 +#define DIO126 126 +#define DIO126_PORT ANALOG12_PORT +#define DIO126_BIT ANALOG12_BIT +#endif +#if (defined(ANALOG13_PORT) && defined(ANALOG13_BIT)) +#define ANALOG13 127 +#define DIO127 127 +#define DIO127_PORT ANALOG13_PORT +#define DIO127_BIT ANALOG13_BIT +#endif +#if (defined(ANALOG14_PORT) && defined(ANALOG14_BIT)) +#define ANALOG14 128 +#define DIO128 128 +#define DIO128_PORT ANALOG14_PORT +#define DIO128_BIT ANALOG14_BIT +#endif +#if (defined(ANALOG15_PORT) && defined(ANALOG15_BIT)) +#define ANALOG15 129 +#define DIO129 129 +#define DIO129_PORT ANALOG15_PORT +#define DIO129_BIT ANALOG15_BIT +#endif +#if (defined(DIN0_PORT) && defined(DIN0_BIT)) +#define DIN0 130 +#define DIO130 130 +#define DIO130_PORT DIN0_PORT +#define DIO130_BIT DIN0_BIT +#endif +#if (defined(DIN1_PORT) && defined(DIN1_BIT)) +#define DIN1 131 +#define DIO131 131 +#define DIO131_PORT DIN1_PORT +#define DIO131_BIT DIN1_BIT +#endif +#if (defined(DIN2_PORT) && defined(DIN2_BIT)) +#define DIN2 132 +#define DIO132 132 +#define DIO132_PORT DIN2_PORT +#define DIO132_BIT DIN2_BIT +#endif +#if (defined(DIN3_PORT) && defined(DIN3_BIT)) +#define DIN3 133 +#define DIO133 133 +#define DIO133_PORT DIN3_PORT +#define DIO133_BIT DIN3_BIT +#endif +#if (defined(DIN4_PORT) && defined(DIN4_BIT)) +#define DIN4 134 +#define DIO134 134 +#define DIO134_PORT DIN4_PORT +#define DIO134_BIT DIN4_BIT +#endif +#if (defined(DIN5_PORT) && defined(DIN5_BIT)) +#define DIN5 135 +#define DIO135 135 +#define DIO135_PORT DIN5_PORT +#define DIO135_BIT DIN5_BIT +#endif +#if (defined(DIN6_PORT) && defined(DIN6_BIT)) +#define DIN6 136 +#define DIO136 136 +#define DIO136_PORT DIN6_PORT +#define DIO136_BIT DIN6_BIT +#endif +#if (defined(DIN7_PORT) && defined(DIN7_BIT)) +#define DIN7 137 +#define DIO137 137 +#define DIO137_PORT DIN7_PORT +#define DIO137_BIT DIN7_BIT +#endif +#if (defined(DIN8_PORT) && defined(DIN8_BIT)) +#define DIN8 138 +#define DIO138 138 +#define DIO138_PORT DIN8_PORT +#define DIO138_BIT DIN8_BIT +#endif +#if (defined(DIN9_PORT) && defined(DIN9_BIT)) +#define DIN9 139 +#define DIO139 139 +#define DIO139_PORT DIN9_PORT +#define DIO139_BIT DIN9_BIT +#endif +#if (defined(DIN10_PORT) && defined(DIN10_BIT)) +#define DIN10 140 +#define DIO140 140 +#define DIO140_PORT DIN10_PORT +#define DIO140_BIT DIN10_BIT +#endif +#if (defined(DIN11_PORT) && defined(DIN11_BIT)) +#define DIN11 141 +#define DIO141 141 +#define DIO141_PORT DIN11_PORT +#define DIO141_BIT DIN11_BIT +#endif +#if (defined(DIN12_PORT) && defined(DIN12_BIT)) +#define DIN12 142 +#define DIO142 142 +#define DIO142_PORT DIN12_PORT +#define DIO142_BIT DIN12_BIT +#endif +#if (defined(DIN13_PORT) && defined(DIN13_BIT)) +#define DIN13 143 +#define DIO143 143 +#define DIO143_PORT DIN13_PORT +#define DIO143_BIT DIN13_BIT +#endif +#if (defined(DIN14_PORT) && defined(DIN14_BIT)) +#define DIN14 144 +#define DIO144 144 +#define DIO144_PORT DIN14_PORT +#define DIO144_BIT DIN14_BIT +#endif +#if (defined(DIN15_PORT) && defined(DIN15_BIT)) +#define DIN15 145 +#define DIO145 145 +#define DIO145_PORT DIN15_PORT +#define DIO145_BIT DIN15_BIT +#endif +#if (defined(DIN16_PORT) && defined(DIN16_BIT)) +#define DIN16 146 +#define DIO146 146 +#define DIO146_PORT DIN16_PORT +#define DIO146_BIT DIN16_BIT +#endif +#if (defined(DIN17_PORT) && defined(DIN17_BIT)) +#define DIN17 147 +#define DIO147 147 +#define DIO147_PORT DIN17_PORT +#define DIO147_BIT DIN17_BIT +#endif +#if (defined(DIN18_PORT) && defined(DIN18_BIT)) +#define DIN18 148 +#define DIO148 148 +#define DIO148_PORT DIN18_PORT +#define DIO148_BIT DIN18_BIT +#endif +#if (defined(DIN19_PORT) && defined(DIN19_BIT)) +#define DIN19 149 +#define DIO149 149 +#define DIO149_PORT DIN19_PORT +#define DIO149_BIT DIN19_BIT +#endif +#if (defined(DIN20_PORT) && defined(DIN20_BIT)) +#define DIN20 150 +#define DIO150 150 +#define DIO150_PORT DIN20_PORT +#define DIO150_BIT DIN20_BIT +#endif +#if (defined(DIN21_PORT) && defined(DIN21_BIT)) +#define DIN21 151 +#define DIO151 151 +#define DIO151_PORT DIN21_PORT +#define DIO151_BIT DIN21_BIT +#endif +#if (defined(DIN22_PORT) && defined(DIN22_BIT)) +#define DIN22 152 +#define DIO152 152 +#define DIO152_PORT DIN22_PORT +#define DIO152_BIT DIN22_BIT +#endif +#if (defined(DIN23_PORT) && defined(DIN23_BIT)) +#define DIN23 153 +#define DIO153 153 +#define DIO153_PORT DIN23_PORT +#define DIO153_BIT DIN23_BIT +#endif +#if (defined(DIN24_PORT) && defined(DIN24_BIT)) +#define DIN24 154 +#define DIO154 154 +#define DIO154_PORT DIN24_PORT +#define DIO154_BIT DIN24_BIT +#endif +#if (defined(DIN25_PORT) && defined(DIN25_BIT)) +#define DIN25 155 +#define DIO155 155 +#define DIO155_PORT DIN25_PORT +#define DIO155_BIT DIN25_BIT +#endif +#if (defined(DIN26_PORT) && defined(DIN26_BIT)) +#define DIN26 156 +#define DIO156 156 +#define DIO156_PORT DIN26_PORT +#define DIO156_BIT DIN26_BIT +#endif +#if (defined(DIN27_PORT) && defined(DIN27_BIT)) +#define DIN27 157 +#define DIO157 157 +#define DIO157_PORT DIN27_PORT +#define DIO157_BIT DIN27_BIT +#endif +#if (defined(DIN28_PORT) && defined(DIN28_BIT)) +#define DIN28 158 +#define DIO158 158 +#define DIO158_PORT DIN28_PORT +#define DIO158_BIT DIN28_BIT +#endif +#if (defined(DIN29_PORT) && defined(DIN29_BIT)) +#define DIN29 159 +#define DIO159 159 +#define DIO159_PORT DIN29_PORT +#define DIO159_BIT DIN29_BIT +#endif +#if (defined(DIN30_PORT) && defined(DIN30_BIT)) +#define DIN30 160 +#define DIO160 160 +#define DIO160_PORT DIN30_PORT +#define DIO160_BIT DIN30_BIT +#endif +#if (defined(DIN31_PORT) && defined(DIN31_BIT)) +#define DIN31 161 +#define DIO161 161 +#define DIO161_PORT DIN31_PORT +#define DIO161_BIT DIN31_BIT +#endif +#if (defined(TX_PORT) && defined(TX_BIT)) +#define TX 200 +#define DIO200 200 +#define DIO200_PORT TX_PORT +#define DIO200_BIT TX_BIT +#endif +#if (defined(RX_PORT) && defined(RX_BIT)) +#define RX 201 +#define DIO201 201 +#define DIO201_PORT RX_PORT +#define DIO201_BIT RX_BIT +#endif +#if (defined(USB_DM_PORT) && defined(USB_DM_BIT)) +#define USB_DM 202 +#define DIO202 202 +#define DIO202_PORT USB_DM_PORT +#define DIO202_BIT USB_DM_BIT +#endif +#if (defined(USB_DP_PORT) && defined(USB_DP_BIT)) +#define USB_DP 203 +#define DIO203 203 +#define DIO203_PORT USB_DP_PORT +#define DIO203_BIT USB_DP_BIT +#endif +#if (defined(SPI_CLK_PORT) && defined(SPI_CLK_BIT)) +#define SPI_CLK 204 +#define DIO204 204 +#define DIO204_PORT SPI_CLK_PORT +#define DIO204_BIT SPI_CLK_BIT +#endif +#if (defined(SPI_SDI_PORT) && defined(SPI_SDI_BIT)) +#define SPI_SDI 205 +#define DIO205 205 +#define DIO205_PORT SPI_SDI_PORT +#define DIO205_BIT SPI_SDI_BIT +#endif +#if (defined(SPI_SDO_PORT) && defined(SPI_SDO_BIT)) +#define SPI_SDO 206 +#define DIO206 206 +#define DIO206_PORT SPI_SDO_PORT +#define DIO206_BIT SPI_SDO_BIT #endif // ISR on change inputs @@ -673,25 +1078,44 @@ extern "C" #if (defined(DIN7_ISR) && defined(DIN7)) #define DIO89_ISR (DIN7_ISR) #define DIN7_ISRCALLBACK mcu_din_isr -#define DIO89_ISRCALLBACK mcu_din_isr +#define DIO89_ISRCALLBACK __indirect__(X, ISRCALLBACK) +#endif + +#if (INTERFACE == INTERFACE_USART) +#ifndef COM_PORT +#define COM_PORT 0 +#endif +#define ENABLE_SYNC_RX +#define ENABLE_SYNC_TX +#define mcu_tx_ready esp8266_uart_tx_ready +#define mcu_rx_ready esp8266_uart_rx_ready +#elif (INTERFACE == INTERFACE_WIFI) +#define ENABLE_SYNC_TX +#define ENABLE_SYNC_RX #endif // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) +#define __indirect__ex__(X, Y) DIO##X##_##Y +#define __indirect__(X, Y) __indirect__ex__(X, Y) + +#define mcu_config_output(X) pinMode(__indirect__(X, BIT), OUTPUT) +#define mcu_config_pwm(X) pinMode(__indirect__(X, BIT), OUTPUT) +#define mcu_config_input(X) pinMode(__indirect__(X, BIT), INPUT) +#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_config_output(X) pinMode(__helper__(X, _BIT, ), OUTPUT) -#define mcu_config_pwm(X) analogWriteMode(__helper__(X, _BIT, ), 0, OUTPUT_OPEN_DRAIN) -#define mcu_config_pwm(X) analogWriteMode(__helper__(X, _BIT, ), 0, OUTPUT_OPEN_DRAIN) -#define mcu_config_input(X) pinMode(__helper__(X, _BIT, ), INPUT) -#define mcu_config_pullup(X) pinMode(__helper__(X, _BIT, ), INPUT_PULLUP) -#define mcu_config_input_isr(X) attachInterrupt(digitalPinToInterrupt(__helper__(X, _BIT, )), __helper__(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) digitalRead(__helper__(X, _BIT, )) -#define mcu_get_output(X) digitalRead(__helper__(X, _BIT, )) -#define mcu_set_output(X) digitalWrite(__helper__(X, _BIT, ), 1) -#define mcu_clear_output(X) digitalWrite(__helper__(X, _BIT, ), 0) -#define mcu_toggle_output(X) digitalWrite(__helper__(X, _BIT, ), !digitalRead(__helper__(X, _BIT, ))) + extern uint8_t esp8266_pwm[16]; +#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = Y) +#define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET]) +#define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) #ifdef __cplusplus } diff --git a/uCNC/src/hal/mcus/mcudefs.h b/uCNC/src/hal/mcus/mcudefs.h index 77f38bce5..35985e002 100644 --- a/uCNC/src/hal/mcus/mcudefs.h +++ b/uCNC/src/hal/mcus/mcudefs.h @@ -57,6 +57,20 @@ extern "C" #endif #endif +#if (MCU == MCU_LPC176X) +#include "lpc176x/mcumap_lpc176x.h" +#ifndef CFG_TUSB_MCU +#define CFG_TUSB_MCU OPT_MCU_LPC175X_6X +#endif +#endif + +#if (MCU == MCU_ESP8266) +#include "esp8266/mcumap_esp8266.h" +#ifndef CFG_TUSB_MCU +#define CFG_TUSB_MCU OPT_MCU_NONE +#endif +#endif + #if (MCU == MCU_VIRTUAL_WIN) #include "virtual/mcumap_virtual.h" #endif diff --git a/uCNC/src/hal/mcus/mcus.h b/uCNC/src/hal/mcus/mcus.h index f140a6dd8..c09b68fa8 100644 --- a/uCNC/src/hal/mcus/mcus.h +++ b/uCNC/src/hal/mcus/mcus.h @@ -29,6 +29,8 @@ extern "C" #define MCU_STM32F1X 10 #define MCU_STM32F4X 11 #define MCU_SAMD21 20 +#define MCU_LPC176X 30 +#define MCU_ESP8266 40 #define MCU_VIRTUAL_WIN 99 #ifdef __cplusplus diff --git a/uCNC/uCNC.ino b/uCNC/uCNC.ino index 97f63da50..0d32aaa80 100644 --- a/uCNC/uCNC.ino +++ b/uCNC/uCNC.ino @@ -1,12 +1,13 @@ #include "src/cnc.h" -int main(void) +void setup() { - // initializes all systems - cnc_init(); + // put your setup code here, to run once: + cnc_init(); +} - for (;;) - { - cnc_run(); - } +void loop() +{ + // put your main code here, to run repeatedly: + cnc_run(); } From 5bda414e24f6030fe00129a28fa2ec5ab7d5327a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 24 Jun 2022 22:22:34 +0100 Subject: [PATCH 03/13] WIFI working --- .../hal/boards/esp8266/boardmap_wemos_d1.h | 14 +- uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp | 82 +++--- uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 242 +++++++++++------- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 80 ++---- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 44 ++-- 5 files changed, 250 insertions(+), 212 deletions(-) diff --git a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h index 50447d3f8..850ec12f0 100644 --- a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h +++ b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h @@ -51,12 +51,14 @@ extern "C" //#define ESTOP_ISR // Setup com pins +#if (INTERFACE == INTERFACE_USART) #define RX_BIT 3 #define TX_BIT 1 #define RX_PORT D #define TX_PORT D - // only uncomment this if other port other then 0 is used - //#define COM_PORT 0 +// only uncomment this if other port other then 0 is used +// #define COM_PORT 0 +#endif // Setup PWM #define PWM0_BIT 2 // assigns PWM0 pin @@ -71,14 +73,6 @@ extern "C" #define STEP0_EN_BIT 0 #define STEP0_EN_PORT D - // Setup the Step Timer used has the heartbeat for µCNC - // Timer 1 is used by default - //#define ITP_TIMER 1 - - // Setup the RTC Timer used by µCNC to provide an (mostly) accurate time base for all time dependent functions - // Timer 0 is set by default - //#define RTC_TIMER 0 - #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp index 2c1f9f5b5..a37ead911 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp @@ -1,38 +1,58 @@ +/* + Name: esp8266_uart.cpp + Description: Contains all Arduino ESP8266 C++ to C functions used by UART in µCNC. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 24-06-2022 + + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + #include "../../../../cnc_config.h" #include #include +#if (INTERFACE == INTERFACE_USART) + extern "C" { - void esp8266_uart_init(int baud) - { - Serial.begin(baud); - } - - char esp8266_uart_read(void) - { - return Serial.read(); - } - - void esp8266_uart_write(char c) - { - Serial.write(c); - } - - bool esp8266_uart_rx_ready(void) - { - return (Serial.available() != 0); - } - - bool esp8266_uart_tx_ready(void) - { - return (Serial.availableForWrite() != 0); - } - - void esp8266_uart_flush(void) - { - Serial.flush(); - } - - void mcu_com_rx_cb(unsigned char c); + void esp8266_com_init(int baud) + { + Serial.begin(baud); + } + + char esp8266_com_read(void) + { + return Serial.read(); + } + + void esp8266_com_write(char c) + { + Serial.write(c); + } + + bool esp8266_com_rx_ready(void) + { + return (Serial.available() != 0); + } + + bool esp8266_com_tx_ready(void) + { + return (Serial.availableForWrite() != 0); + } + + void esp8266_com_flush(void) + { + Serial.flush(); + } } + +#endif diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp index bd2e192f0..d65447dd4 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp @@ -1,5 +1,24 @@ -//#include "Arduino.h" +/* +Name: esp8266_wifi.cpp +Description: Contains all Arduino ESP8266 C++ to C functions used by WiFi in µCNC. + +Copyright: Copyright (c) João Martins +Author: João Martins +Date: 24-06-2022 + +µCNC is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. Please see + +µCNC is distributed WITHOUT ANY WARRANTY; +Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +See the GNU General Public License for more details. +*/ + #include "../../../../cnc_config.h" + +#if (INTERFACE == INTERFACE_WIFI) #include #include #include @@ -7,12 +26,11 @@ #include #include #include -#include #include -#include +#include -#ifndef WIFI_BUFFER -#define WIFI_BUFFER 128 +#ifndef WIFI_BUFFER_SIZE +#define WIFI_BUFFER_SIZE 255 #endif #ifndef WIFI_PORT @@ -36,100 +54,144 @@ const char *update_password = WIFI_PASS; WiFiServer server(WIFI_PORT); WiFiClient serverClient; WiFiManager wifiManager; +typedef struct wifi_rxbuffer_ +{ + char buffer[WIFI_BUFFER_SIZE]; + uint8_t len; + uint8_t current; +} wifi_rxbuffer_t; + +static wifi_rxbuffer_t wifi_rx_buffer; +static wifi_rxbuffer_t wifi_tx_buffer; + +bool esp8266_wifi_clientok(void) +{ + if (server.hasClient()) + { + if (serverClient && serverClient.connected()) + { + serverClient.stop(); + } + serverClient = server.available(); +#ifdef WIFI_DEBUG + Serial.println("[MSG: New client accepted]"); +#endif + serverClient.write("[MSG: New client connected]\r\n"); + return false; + } + else if (serverClient && serverClient.connected()) + { + return true; + } + + return false; +} extern "C" { - void esp8266_wifi_init(void) - { + void esp8266_com_init(void) + { #ifdef WIFI_DEBUG - Serial.begin(115200); - wifiManager.setDebugOutput(true); + Serial.setRxBufferSize(1024); + Serial.begin(115200); + wifiManager.setDebugOutput(true); #else - wifiManager.setDebugOutput(false); -#endif - wifiManager.autoConnect("ESP8266"); -#ifdef WIFI_DEBUG - Serial.println("[MSG: WiFi manager up]"); + wifiManager.setDebugOutput(false); #endif + wifiManager.autoConnect("ESP8266"); #ifdef WIFI_DEBUG - Serial.println("[MSG: Setup page @ 192.168.4.1]"); -#endif - server.setNoDelay(true); - httpUpdater.setup(&httpServer, update_path, update_username, update_password); - httpServer.begin(); - WiFi.setSleepMode(WIFI_NONE_SLEEP); + Serial.println("[MSG: WiFi manager up]"); + Serial.println("[MSG: Setup page @ 192.168.4.1]"); +#endif + server.begin(); + server.setNoDelay(true); + httpUpdater.setup(&httpServer, update_path, update_username, update_password); + httpServer.begin(); + WiFi.setSleepMode(WIFI_NONE_SLEEP); -#ifdef WIFI_DEBUG - Serial.println("[MSG: WiFi server us up]"); -#endif - } + memset(wifi_rx_buffer.buffer, 0, WIFI_BUFFER_SIZE); + wifi_rx_buffer.len = 0; + wifi_rx_buffer.current = 0; - void esp8266_wifi_read(void (*read_callback)(unsigned char)) - { - if (server.hasClient()) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: client waiting]"); -#endif - if (serverClient && serverClient.connected()) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: kill old client]"); -#endif - serverClient.stop(); - } + memset(wifi_tx_buffer.buffer, 0, WIFI_BUFFER_SIZE); + wifi_tx_buffer.len = 0; + wifi_tx_buffer.current = 0; + } -#ifdef WIFI_DEBUG - Serial.println("[MSG: client started]"); -#endif - } - else if (serverClient && serverClient.connected()) - { - size_t rxlen = serverClient.available(); - if (rxlen > 0) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: client has data]"); -#endif - uint8_t sbuf[rxlen]; - serverClient.readBytes(sbuf, rxlen); - for (uint8_t i = 0; i < rxlen; i++) - { - if (read_callback) - { - read_callback((unsigned char)sbuf[i]); - } - yield(); - } - } - } - } - - void esp8266_wifi_write(char *buff, uint8_t len) - { - if (server.hasClient()) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: client waiting]"); -#endif - if (serverClient && serverClient.connected()) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: kill old client]"); -#endif - serverClient.stop(); - } + char esp8266_com_read(void) + { + if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) + { + return wifi_rx_buffer.buffer[wifi_rx_buffer.current++]; + } -#ifdef WIFI_DEBUG - Serial.println("[MSG: client started]"); -#endif - } - else if (serverClient && serverClient.connected()) - { -#ifdef WIFI_DEBUG - Serial.println("[MSG: sent data to client]"); -#endif - serverClient.write(buff, (size_t)len); - } - } + if (esp8266_wifi_clientok()) + { + size_t rxlen = serverClient.available(); + if (rxlen > 0) + { + serverClient.readBytes(wifi_rx_buffer.buffer, rxlen); + wifi_rx_buffer.len = rxlen; + wifi_rx_buffer.current = 1; + return wifi_rx_buffer.buffer[0]; + } + } + + return 0; + } + + void esp8266_com_write(char c) + { + if (esp8266_wifi_clientok()) + { + wifi_tx_buffer.buffer[wifi_tx_buffer.len] = c; + wifi_tx_buffer.len++; + if (c == '\n') + { + serverClient.write(wifi_tx_buffer.buffer, (size_t)wifi_tx_buffer.len); + memset(wifi_tx_buffer.buffer, 0, WIFI_BUFFER_SIZE); + wifi_tx_buffer.len = 0; + } + } + } + + bool esp8266_com_rx_ready(void) + { + if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) + { + return true; + } + + if (esp8266_wifi_clientok()) + { + return (serverClient.available() != 0); + } + + return false; + } + + bool esp8266_com_tx_ready(void) + { + if (esp8266_wifi_clientok()) + { + if (wifi_tx_buffer.len < WIFI_BUFFER_SIZE) + { + return true; + } + } + + return false; + } + + void esp8266_com_flush(void) + { + if (esp8266_wifi_clientok()) + { + serverClient.flush(); + } + + httpServer.handleClient(); + } } + +#endif diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 88a8a0e58..ae9d217bd 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -4,7 +4,7 @@ Copyright: Copyright (c) João Martins Author: João Martins - Date: 04-02-2022 + Date: 05-02-2022 µCNC is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -42,18 +42,12 @@ static volatile bool esp8266_global_isr_enabled; static volatile uint32_t mcu_runtime_ms; uint8_t esp8266_pwm[16]; -char esp8266_tx_buffer[TX_BUFFER_SIZE - 2]; -char esp8266_rx_buffer[RX_BUFFER_SIZE]; -char *tx_ptr; -void esp8266_wifi_init(void); -void esp8266_wifi_read(void (*read_callback)(unsigned char)); -void esp8266_wifi_write(char *buff, uint8_t len); -void esp8266_uart_init(int baud); -char esp8266_uart_read(void); -void esp8266_uart_write(char c); -bool esp8266_uart_rx_ready(void); -bool esp8266_uart_tx_ready(void); -void esp8266_uart_flush(void); +void esp8266_com_init(int baud); +char esp8266_com_read(void); +void esp8266_com_write(char c); +bool esp8266_com_rx_ready(void); +bool esp8266_com_tx_ready(void); +void esp8266_com_flush(void); ETSTimer esp8266_rtc_timer; @@ -296,11 +290,7 @@ IRAM_ATTR void mcu_itp_isr(void) void mcu_usart_init(void) { -#if (INTERFACE == INTERFACE_USART) - esp8266_uart_init(BAUDRATE); -#elif (INTERFACE == INTERFACE_WIFI) - esp8266_wifi_init(); -#endif + esp8266_com_init(BAUDRATE); } /** * initializes the mcu @@ -970,7 +960,6 @@ void mcu_init(void) mcu_config_output(SPI_SDO); #endif - tx_ptr = esp8266_tx_buffer; mcu_usart_init(); // init rtc @@ -1039,7 +1028,7 @@ uint8_t mcu_get_pwm(uint8_t pwm) #ifndef mcu_tx_ready bool mcu_tx_ready(void) { - return esp8266_uart_tx_ready(); + return esp8266_com_tx_ready(); } #endif @@ -1049,7 +1038,7 @@ bool mcu_tx_ready(void) #ifndef mcu_rx_ready bool mcu_rx_ready(void) { - return esp8266_uart_rx_ready(); + return esp8266_com_rx_ready(); } #endif @@ -1064,29 +1053,11 @@ void mcu_putc(char c) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) #ifdef ENABLE_SYNC_TX while (!mcu_tx_ready()) ; #endif - esp8266_uart_write(c); -#elif (INTERFACE == INTERFACE_WIFI) - if (c != 0) - { - *tx_ptr = c; - tx_ptr++; - tx_ptr = 0; - } - if (c == '\r' || c == 0) - { - *tx_ptr = c; - tx_ptr++; - tx_ptr = 0; - uint8_t len = strlen(esp8266_tx_buffer); - esp8266_wifi_write(esp8266_tx_buffer, len); - tx_ptr = esp8266_tx_buffer; - } -#endif + esp8266_com_write(c); } #endif @@ -1100,15 +1071,11 @@ char mcu_getc(void) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) #ifdef ENABLE_SYNC_RX while (!mcu_rx_ready()) ; #endif - return esp8266_uart_read(); -#elif (INTERFACE == INTERFACE_WIFI) -#endif - return 0; + return esp8266_com_read(); } #endif @@ -1120,7 +1087,7 @@ char mcu_getc(void) #ifndef mcu_enable_global_isr void mcu_enable_global_isr(void) { - //ets_intr_unlock(); + // ets_intr_unlock(); esp8266_global_isr_enabled = true; } #endif @@ -1133,7 +1100,7 @@ void mcu_enable_global_isr(void) void mcu_disable_global_isr(void) { esp8266_global_isr_enabled = false; - //ets_intr_lock(); + // ets_intr_lock(); } #endif @@ -1201,11 +1168,12 @@ uint32_t mcu_millis() } #ifndef mcu_delay_us - void mcu_delay_us(uint8_t delay) - { - uint32_t time = system_get_time() + delay; - while(time>system_get_time()); - } +void mcu_delay_us(uint8_t delay) +{ + uint32_t time = system_get_time() + delay; + while (time > system_get_time()) + ; +} #endif /** @@ -1220,9 +1188,8 @@ void mcu_dotasks(void) // reset WDT system_soft_wdt_feed(); -#if (INTERFACE == INTERFACE_USART) -#ifdef ENABLE_SYNC_TX - esp8266_uart_flush(); +#if (defined(ENABLE_SYNC_TX) || defined(ENABLE_SYNC_RX)) + esp8266_com_flush(); #endif #ifdef ENABLE_SYNC_RX while (mcu_rx_ready()) @@ -1231,9 +1198,6 @@ void mcu_dotasks(void) mcu_com_rx_cb(c); } #endif -#elif (INTERFACE == INTERFACE_WIFI) - esp8266_wifi_read(mcu_com_rx_cb); -#endif } // Non volatile memory diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index e6ec2fb0b..6de9e7efd 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1,19 +1,19 @@ /* - Name: mcumap_esp8266.h - Description: Contains all MCU and PIN definitions for Arduino ESP8266 to run µCNC. + Name: mcumap_esp8266.h + Description: Contains all MCU and PIN definitions for Arduino ESP8266 to run µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 04-02-2020 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 05-02-2022 - µCNC is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. Please see + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see - µCNC is distributed WITHOUT ANY WARRANTY; - Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU General Public License for more details. + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. */ #ifndef MCUMAP_ESP8266_H @@ -27,15 +27,15 @@ extern "C" #include /* - Generates all the interface definitions. - This creates a middle HAL layer between the board IO pins and the AVR funtionalities + Generates all the interface definitions. + This creates a middle HAL layer between the board IO pins and the AVR funtionalities */ /* - MCU specific definitions and replacements + MCU specific definitions and replacements */ /* - ESP8266 Defaults + ESP8266 Defaults */ // defines the frequency of the mcu #ifndef F_CPU @@ -1085,14 +1085,12 @@ extern "C" #ifndef COM_PORT #define COM_PORT 0 #endif +#endif + #define ENABLE_SYNC_RX #define ENABLE_SYNC_TX -#define mcu_tx_ready esp8266_uart_tx_ready -#define mcu_rx_ready esp8266_uart_rx_ready -#elif (INTERFACE == INTERFACE_WIFI) -#define ENABLE_SYNC_TX -#define ENABLE_SYNC_RX -#endif +#define mcu_tx_ready esp8266_com_tx_ready +#define mcu_rx_ready esp8266_com_rx_ready // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) @@ -1112,7 +1110,7 @@ extern "C" #define mcu_clear_output(X) digitalWrite(__indirect__(X, BIT), 0) #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) - extern uint8_t esp8266_pwm[16]; + extern uint8_t esp8266_pwm[16]; #define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = Y) #define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET]) #define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) From e4ee23be3cf93dffa43b6e266b9a78a65f92fae3 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 26 Jun 2022 23:09:13 +0100 Subject: [PATCH 04/13] EEPROM not working --- platformio.ini | 2 +- uCNC/cnc_config.h | 433 ++++++++++--------- uCNC/src/cnc_build.h | 4 +- uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp | 30 ++ uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 203 ++++++--- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 4 +- uCNC/src/hal/mcus/mcu.h | 2 +- 7 files changed, 410 insertions(+), 268 deletions(-) create mode 100644 uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp diff --git a/platformio.ini b/platformio.ini index 5c4767902..c237c90d1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -100,5 +100,5 @@ platform = espressif8266 framework = arduino board = d1 lib_deps = - WiFiManager + tzapu/WiFiManager build_flags = -I include -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index abbe9b3a3..b4b265925 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -1,19 +1,19 @@ /* - Name: cnc_config.h - Description: Compile time configurations for µCNC. + Name: cnc_config.h + Description: Compile time configurations for µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 19/09/2019 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 19/09/2019 - µCNC is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. Please see + µCNC is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. Please see - µCNC is distributed WITHOUT ANY WARRANTY; - Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. */ @@ -27,12 +27,13 @@ extern "C" #define INTERFACE_USART 0 #define INTERFACE_USB 1 +#define INTERFACE_WIFI 2 - /** - * Serial COM - * Defines the serial COM baud rate - * Uses 1 start bit + 8 bit + 1 stop bit (no parity) - * */ + /** + * Serial COM + * Defines the serial COM baud rate + * Uses 1 start bit + 8 bit + 1 stop bit (no parity) + * */ #ifndef BAUDRATE #define BAUDRATE 115200 @@ -42,20 +43,20 @@ extern "C" #define INTERFACE INTERFACE_USART #endif - /** - * uncomment to force enable synchronized TX/RX (used in USB VCP) - * enable these options to perform comunications in the mcu tasks function - * call instead of being interrupt driven (sync RX may cause problems with - * hardware USART) - * */ + /** + * uncomment to force enable synchronized TX/RX (used in USB VCP) + * enable these options to perform comunications in the mcu tasks function + * call instead of being interrupt driven (sync RX may cause problems with + * hardware USART) + * */ - // #define ENABLE_SYNC_TX - // #define ENABLE_SYNC_RX + // #define ENABLE_SYNC_TX + // #define ENABLE_SYNC_RX - /** - * Choose the board - * Check boardss.h for list of available/supported boards - * */ + /** + * Choose the board + * Check boardss.h for list of available/supported boards + * */ #ifndef BOARD #define BOARD BOARD_UNO @@ -66,14 +67,14 @@ extern "C" //#define BOARD_NAME "My custom board" #endif - /** - * Kinematic - * - * Defines axis count - * Defines the machine kinematics (cartesian, corexy, delta, custom, ...) - * For custom/advanced configurations go to the specified kinematics header - * file - * */ + /** + * Kinematic + * + * Defines axis count + * Defines the machine kinematics (cartesian, corexy, delta, custom, ...) + * For custom/advanced configurations go to the specified kinematics header + * file + * */ #ifndef AXIS_COUNT #define AXIS_COUNT 3 @@ -83,42 +84,42 @@ extern "C" #define KINEMATIC KINEMATIC_CARTESIAN #endif - /** - * Defines the number of supported coordinate systems supported by µCNC - * Can be any value between 1 and 9 - * */ + /** + * Defines the number of supported coordinate systems supported by µCNC + * Can be any value between 1 and 9 + * */ #define COORD_SYS_COUNT 6 - /** - * Number of segments of an arc computed with aprox. of sin/cos math - * operation before performing a full calculation - * */ + /** + * Number of segments of an arc computed with aprox. of sin/cos math + * operation before performing a full calculation + * */ #define N_ARC_CORRECTION 16 - /** - * Echo recieved commands. - * Uncomment to enable. Only necessary to debug communication problems - * */ + /** + * Echo recieved commands. + * Uncomment to enable. Only necessary to debug communication problems + * */ - //#define ECHO_CMD + //#define ECHO_CMD - /** - * Sets/limits the number of tools to be used - * The tool and tool order are configured in the cnc_hal_config.h - * */ + /** + * Sets/limits the number of tools to be used + * The tool and tool order are configured in the cnc_hal_config.h + * */ #ifndef TOOL_COUNT #define TOOL_COUNT 1 #endif #if TOOL_COUNT > 0 - /** - * Number of seconds of delay before motions restart after releasing from a - * hold or after setting a new spindle speed This is used by spindle to - * ensure spindle gets up to speed in motions - * */ + /** + * Number of seconds of delay before motions restart after releasing from a + * hold or after setting a new spindle speed This is used by spindle to + * ensure spindle gets up to speed in motions + * */ #define DELAY_ON_RESUME_SPINDLE 4 #define DELAY_ON_SPINDLE_SPEED_CHANGE 1 @@ -130,25 +131,25 @@ extern "C" //#define M7_SAME_AS_M8 #endif - /** - * Feed overrides increments and percentage ranges - * */ + /** + * Feed overrides increments and percentage ranges + * */ #define FEED_OVR_MAX 200 #define FEED_OVR_MIN 10 #define FEED_OVR_COARSE 10 #define FEED_OVR_FINE 1 - /** - * Rapid feed overrides percentages - * */ + /** + * Rapid feed overrides percentages + * */ #define RAPID_FEED_OVR1 50 #define RAPID_FEED_OVR2 25 - /** - * Spindle speed overrides increments percentages and ranges - * */ + /** + * Spindle speed overrides increments percentages and ranges + * */ #define SPINDLE_OVR_MAX 200 #define SPINDLE_OVR_MIN 10 @@ -180,27 +181,27 @@ extern "C" //#define GCODE_COUNT_TEXT_LINES #endif - /** - * processes comment as defined in the RS274NGC - * */ + /** + * processes comment as defined in the RS274NGC + * */ - //#define PROCESS_COMMENTS + //#define PROCESS_COMMENTS - /** - * Enables RS274NGC canned cycles - * */ + /** + * Enables RS274NGC canned cycles + * */ - // #define ENABLE_CANNED_CYCLES + // #define ENABLE_CANNED_CYCLES - /** - * accepts the E word (currently is processed has A) - * */ + /** + * accepts the E word (currently is processed has A) + * */ - //#define GCODE_ACCEPT_WORD_E + //#define GCODE_ACCEPT_WORD_E - /** - * Uncomment to enable module extensions - * */ + /** + * Uncomment to enable module extensions + * */ // #define ENABLE_MAIN_LOOP_MODULES // #define ENABLE_IO_MODULES // #define ENABLE_PARSER_MODULES @@ -219,22 +220,22 @@ extern "C" // values bellow 100ms have no effect #define STATUS_AUTOMATIC_REPORT_INTERVAL 0 - /** - * - * Enable this option to set home has your machine origin. - * When a machine homes each axis is set to 0 or max_axis_distance (settings $13x) depending on if the home direction invert mask is turned on or off (settting $23) - * In practice $23 sets if the machine homes towards the orgin (default) or away from the origin (inverted) - * After homing the machine coordinate system is set in a way that the workable volume has always positive coordinates. - * By enabling this option after homing the machine will set the homing position has it's origin. - * Because of this the machine coordinate system might be offset to negative dimensions in some axis. - * */ + /** + * + * Enable this option to set home has your machine origin. + * When a machine homes each axis is set to 0 or max_axis_distance (settings $13x) depending on if the home direction invert mask is turned on or off (settting $23) + * In practice $23 sets if the machine homes towards the orgin (default) or away from the origin (inverted) + * After homing the machine coordinate system is set in a way that the workable volume has always positive coordinates. + * By enabling this option after homing the machine will set the homing position has it's origin. + * Because of this the machine coordinate system might be offset to negative dimensions in some axis. + * */ - // #define SET_ORIGIN_AT_HOME_POS + // #define SET_ORIGIN_AT_HOME_POS - /** - * If the type of machine supports skew and needs skew correction - * (defined in the specified kinematics_xxx.h file) - * */ + /** + * If the type of machine supports skew and needs skew correction + * (defined in the specified kinematics_xxx.h file) + * */ // #define ENABLE_SKEW_COMPENSATION #ifdef ENABLE_SKEW_COMPENSATION @@ -242,86 +243,86 @@ extern "C" //#define SKEW_COMPENSATION_XY_ONLY #endif - /** - * Changes the planner acceleration profile generation from axis driven to - * linear actuator driven - * */ + /** + * Changes the planner acceleration profile generation from axis driven to + * linear actuator driven + * */ - //#define ENABLE_LINACT_PLANNER + //#define ENABLE_LINACT_PLANNER #ifdef ENABLE_LINACT_PLANNER - // uncomment to do a stop and start if any of the linear actuators is at a - // still state or changes direction - //#define ENABLE_LINACT_COLD_START + // uncomment to do a stop and start if any of the linear actuators is at a + // still state or changes direction + //#define ENABLE_LINACT_COLD_START #endif - /** - * If the type of machine need backlash compensation configure here - * */ + /** + * If the type of machine need backlash compensation configure here + * */ - // #define ENABLE_BACKLASH_COMPENSATION + // #define ENABLE_BACKLASH_COMPENSATION - /** - * Uncomment these to enable step ISR calculation strategies (uses more - * memory) STEP_ISR_SKIP_MAIN - carries the information about the main - * stepper (performs a step in every ISR tick) and skips calculations - * STEP_ISR_SKIP_IDLE - carries the information about the idle steppers - * (performs 0 steps in the ISR tick) and skips calculations - * */ + /** + * Uncomment these to enable step ISR calculation strategies (uses more + * memory) STEP_ISR_SKIP_MAIN - carries the information about the main + * stepper (performs a step in every ISR tick) and skips calculations + * STEP_ISR_SKIP_IDLE - carries the information about the idle steppers + * (performs 0 steps in the ISR tick) and skips calculations + * */ #define STEP_ISR_SKIP_MAIN #define STEP_ISR_SKIP_IDLE - /** - * Sets the maximum number of step doubling loops carried by the DSS (Dynamic - * Step Spread) algorithm (Similar to Grbl AMASS). The DSS algorithm allows - * to spread stepps by over sampling bresenham line algorithm at lower - * frequencies and reduce vibrations of the stepper motors Value should range - * from 0 to 3. With a value o 0 the DSS will be disabled. - * */ + /** + * Sets the maximum number of step doubling loops carried by the DSS (Dynamic + * Step Spread) algorithm (Similar to Grbl AMASS). The DSS algorithm allows + * to spread stepps by over sampling bresenham line algorithm at lower + * frequencies and reduce vibrations of the stepper motors Value should range + * from 0 to 3. With a value o 0 the DSS will be disabled. + * */ #define DSS_MAX_OVERSAMPLING 3 #define DSS_CUTOFF_FREQ 500 - /** - * Modifies the bresenham algorithm to use a 16-version (experimental). - * This uses less memory, faster ISR stepping, but increases motion and - * planner calculations since line segments are divided into smaller - * segments. - * */ + /** + * Modifies the bresenham algorithm to use a 16-version (experimental). + * This uses less memory, faster ISR stepping, but increases motion and + * planner calculations since line segments are divided into smaller + * segments. + * */ - // #define BRESENHAM_16BIT + // #define BRESENHAM_16BIT - /** - * Performs motions with variable acceleration (trapezoidal speed profile - * with roundend speed transition between accel/deaccel and constant speed) - * instead of constant acceleration (trapezoizal speed profile) - * - * */ + /** + * Performs motions with variable acceleration (trapezoidal speed profile + * with roundend speed transition between accel/deaccel and constant speed) + * instead of constant acceleration (trapezoizal speed profile) + * + * */ - // #define ENABLE_S_CURVE_ACCELERATION + // #define ENABLE_S_CURVE_ACCELERATION - /** - * Enables legacy step interpolation generator (prior to version 1.4) - * This runs a variable time window Riemman sum integrator (better performance). - * S-Curve acceleration will disable this option - * This produces option outputs code smaller size - * */ + /** + * Enables legacy step interpolation generator (prior to version 1.4) + * This runs a variable time window Riemman sum integrator (better performance). + * S-Curve acceleration will disable this option + * This produces option outputs code smaller size + * */ #define USE_LEGACY_STEP_INTERPOLATOR - /** - * Forces pin pooling for all limits and control pins (with or without - * interrupts) - * */ + /** + * Forces pin pooling for all limits and control pins (with or without + * interrupts) + * */ - //#define FORCE_SOFT_POLLING + //#define FORCE_SOFT_POLLING - /** - * Runs a check for state change inside the scheduler. This is a failsafe - * check to pin ISR checking The value sets the frequency of this safety - * check that is executed every 2^(CONTROLS_SCHEDULE_CHECK) milliseconds. A - * negative value will disable this feature. The maximum is 7 - * */ + /** + * Runs a check for state change inside the scheduler. This is a failsafe + * check to pin ISR checking The value sets the frequency of this safety + * check that is executed every 2^(CONTROLS_SCHEDULE_CHECK) milliseconds. A + * negative value will disable this feature. The maximum is 7 + * */ #define CTRL_SCHED_CHECK 4 @@ -332,85 +333,105 @@ extern "C" // #define INVERT_EMERGENCY_STOP #endif - /** - * Disable/enable all control, limits or/and probing input pins. This - * helps to reduce code size if features are not needed - * */ + /** + * Disable/enable all control, limits or/and probing input pins. This + * helps to reduce code size if features are not needed + * */ #ifndef DISABLE_ALL_CONTROLS // #define DISABLE_ALL_CONTROLS #endif #ifndef DISABLE_ALL_LIMITS - // #define DISABLE_ALL_LIMITS + // #define DISABLE_ALL_LIMITS #endif #ifndef DISABLE_PROBE // #define DISABLE_PROBE #endif - /** - * Modifies the startup message to emulate Grbl (required by some programs so - * that uCNC is recognized a Grbl protocol controller device) - * */ + /** + * Modifies the startup message to emulate Grbl (required by some programs so + * that uCNC is recognized a Grbl protocol controller device) + * */ #define EMULATE_GRBL_STARTUP - /** - * - * Enables $I Grbl info command on µCNC. - * - * */ + /** + * + * Enables $I Grbl info command on µCNC. + * + * */ #define ENABLE_SYSTEM_INFO - /** - * Enables aditional grbl-type commands - * For settings allows settings to only be stored in EEPROM/Flash explicitly - * on special command This makes that all $= - * commands are only performed in SRAM and not stored directly to - * EEPROM/Flash A few commands are added: $SS - Settings store - records - * settings from SRAM to EEPROM/Flash $SL - Settings load - Loads settings - * from EEPROM/Flash to SRAM $SR - Settings reset - Reloads the default value - * settings from ROM to SRAM - * - * For pin diagnostics enables command $P - * */ + /** + * Enables aditional grbl-type commands + * For settings allows settings to only be stored in EEPROM/Flash explicitly + * on special command This makes that all $= + * commands are only performed in SRAM and not stored directly to + * EEPROM/Flash A few commands are added: $SS - Settings store - records + * settings from SRAM to EEPROM/Flash $SL - Settings load - Loads settings + * from EEPROM/Flash to SRAM $SR - Settings reset - Reloads the default value + * settings from ROM to SRAM + * + * For pin diagnostics enables command $P + * */ - // #define ENABLE_EXTRA_SYSTEM_CMDS +// #define ENABLE_EXTRA_SYSTEM_CMDS - /** - * Compilation specific options - * */ + /** + * Compilation specific options + * */ - /** - * forces all global variables are set to 0 at start up - * this shoud not be necessary since the linker usually performs this task - * */ + /** + * forces all global variables are set to 0 at start up + * this shoud not be necessary since the linker usually performs this task + * */ - // #define FORCE_GLOBALS_TO_0 + // #define FORCE_GLOBALS_TO_0 - /** - * saves a little program memory bytes but much more slow CRC check - * */ + /** + * saves a little program memory bytes but much more slow CRC check + * */ #define CRC_WITHOUT_LOOKUP_TABLE - /** - * This uses RAM only settings - * Storing is disabled and the defaults will be loaded at each powerup - * This is usefull if you don't have EEPROM/FLASH storage or the devide read/write maximum cycle count is low to prevent damage - * */ - // #define RAM_ONLY_SETTINGS + /** + * This uses RAM only settings + * Storing is disabled and the defaults will be loaded at each powerup + * This is usefull if you don't have EEPROM/FLASH storage or the devide read/write maximum cycle count is low to prevent damage + * */ + // #define RAM_ONLY_SETTINGS + /** + * EXPERIMENTAL! Uncomment to enable fast math macros to reduce the number of + * required cpu cycles needed for a few math operations (mainly on 8-bit + * processors) This will affect the feed rate precision in about ~5%. Output + * binary will be bigger. No fast math macros are and shoud be used in + * functions that calculate coordinates to avoid positional errors except + * multiply and divide by powers of 2 macros + * */ - /** - * EXPERIMENTAL! Uncomment to enable fast math macros to reduce the number of - * required cpu cycles needed for a few math operations (mainly on 8-bit - * processors) This will affect the feed rate precision in about ~5%. Output - * binary will be bigger. No fast math macros are and shoud be used in - * functions that calculate coordinates to avoid positional errors except - * multiply and divide by powers of 2 macros - * */ + // #define ENABLE_FAST_MATH - // #define ENABLE_FAST_MATH +/** + * + * HAL offsets + * + * */ +#ifndef PWM_PINS_OFFSET +#define PWM_PINS_OFFSET 24 +#endif +#ifndef SERVO_PINS_OFFSET +#define SERVO_PINS_OFFSET 40 +#endif +#ifndef DOUT_PINS_OFFSET +#define DOUT_PINS_OFFSET 46 +#endif +#ifndef ANALOG_PINS_OFFSET +#define ANALOG_PINS_OFFSET 114 +#endif +#ifndef DIN_PINS_OFFSET +#define DIN_PINS_OFFSET 130 +#endif #ifdef __cplusplus } diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index ca6461161..8a527f788 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -24,8 +24,8 @@ extern "C" { #endif -#define CNC_MAJOR_MINOR_VERSION "1.5" -#define CNC_PATCH_VERSION ".alpha" +#define CNC_MAJOR_MINOR_VERSION "1.4" +#define CNC_PATCH_VERSION ".6pre" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp new file mode 100644 index 000000000..097da3e5b --- /dev/null +++ b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp @@ -0,0 +1,30 @@ +#include "../../../../cnc_config.h" + +#ifndef RAM_ONLY_SETTINGS +#include +#include +#include +extern "C" +{ + void esp8266_eeprom_init(int size) + { + EEPROM.begin(size); + } + + void esp8266_eeprom_read(uint16_t address) + { + EEPROM.read(address); + } + + void esp8266_eeprom_write(uint16_t address, uint8_t value) + { + EEPROM.write(address, value); + } + + void esp8266_eeprom_flush(void) + { + EEPROM.commit(); + } +} + +#endif \ No newline at end of file diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index ae9d217bd..88df639b3 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -40,7 +40,6 @@ static volatile bool esp8266_global_isr_enabled; static volatile uint32_t mcu_runtime_ms; -uint8_t esp8266_pwm[16]; void esp8266_com_init(int baud); char esp8266_com_read(void); @@ -51,32 +50,12 @@ void esp8266_com_flush(void); ETSTimer esp8266_rtc_timer; -IRAM_ATTR void mcu_din_isr(void) -{ - io_inputs_isr(); -} - -IRAM_ATTR void mcu_probe_isr(void) -{ - io_probe_isr(); -} - -IRAM_ATTR void mcu_limits_isr(void) -{ - io_limits_isr(); -} - -IRAM_ATTR void mcu_controls_isr(void) -{ - io_controls_isr(); -} - -IRAM_ATTR void mcu_rtc_isr(void *arg) +uint8_t esp8266_pwm[16]; +static IRAM_ATTR void mcu_gen_pwm(void) { static uint8_t pwm_counter = 0; - mcu_runtime_ms++; // software PWM - if (++pwm_counter) + if (++pwm_counter < 127) { #if !(PWM0 < 0) if (pwm_counter > esp8266_pwm[0]) @@ -177,69 +156,163 @@ IRAM_ATTR void mcu_rtc_isr(void *arg) } else { + pwm_counter = 0; #if !(PWM0 < 0) - mcu_set_output(PWM0); + if (esp8266_pwm[0]) + { + mcu_set_output(PWM0); + } #endif #if !(PWM1 < 0) - mcu_set_output(PWM1); + if (esp8266_pwm[1]) + { + mcu_set_output(PWM1); + } #endif #if !(PWM2 < 0) - mcu_set_output(PWM2); + if (esp8266_pwm[2]) + { + mcu_set_output(PWM2); + } #endif #if !(PWM3 < 0) - mcu_set_output(PWM3); + if (esp8266_pwm[3]) + { + mcu_set_output(PWM3); + } #endif #if !(PWM4 < 0) - mcu_set_output(PWM4); + if (esp8266_pwm[4]) + { + mcu_set_output(PWM4); + } #endif #if !(PWM5 < 0) - mcu_set_output(PWM5); + if (esp8266_pwm[5]) + { + mcu_set_output(PWM5); + } #endif #if !(PWM6 < 0) - mcu_set_output(PWM6); + if (esp8266_pwm[6]) + { + mcu_set_output(PWM6); + } #endif #if !(PWM7 < 0) - mcu_set_output(PWM7); + if (esp8266_pwm[7]) + { + mcu_set_output(PWM7); + } #endif #if !(PWM8 < 0) - mcu_set_output(PWM8); + if (esp8266_pwm[8]) + { + mcu_set_output(PWM8); + } #endif #if !(PWM9 < 0) - mcu_set_output(PWM9); + if (esp8266_pwm[9]) + { + mcu_set_output(PWM9); + } #endif #if !(PWM10 < 0) - mcu_set_output(PWM10); + if (esp8266_pwm[10]) + { + mcu_set_output(PWM10); + } #endif #if !(PWM11 < 0) - mcu_set_output(PWM11); + if (esp8266_pwm[11]) + { + mcu_set_output(PWM11); + } #endif #if !(PWM12 < 0) - mcu_set_output(PWM12); + if (esp8266_pwm[12]) + { + mcu_set_output(PWM12); + } #endif #if !(PWM13 < 0) - mcu_set_output(PWM13); + if (esp8266_pwm[13]) + { + mcu_set_output(PWM13); + } #endif #if !(PWM14 < 0) - mcu_set_output(PWM14); + if (esp8266_pwm[14]) + { + mcu_set_output(PWM14); + } #endif #if !(PWM15 < 0) - mcu_set_output(PWM15); + if (esp8266_pwm[15]) + { + mcu_set_output(PWM15); + } #endif } +} + +static uint32_t mcu_step_counter; +static uint32_t mcu_step_reload; +static IRAM_ATTR void mcu_gen_step(void) +{ + if (mcu_step_reload) + { + if (!--mcu_step_counter) + { + static bool resetstep = false; + if (!resetstep) + mcu_step_cb(); + else + mcu_step_reset_cb(); + resetstep = !resetstep; + mcu_step_counter = mcu_step_reload; + } + } +} + +IRAM_ATTR void mcu_din_isr(void) +{ + io_inputs_isr(); +} +IRAM_ATTR void mcu_probe_isr(void) +{ + io_probe_isr(); +} + +IRAM_ATTR void mcu_limits_isr(void) +{ + io_limits_isr(); +} + +IRAM_ATTR void mcu_controls_isr(void) +{ + io_controls_isr(); +} + +IRAM_ATTR void mcu_rtc_isr(void *arg) +{ + mcu_runtime_ms++; mcu_rtc_cb(mcu_runtime_ms); } IRAM_ATTR void mcu_itp_isr(void) { - mcu_disable_global_isr(); - static bool resetstep = false; - if (!resetstep) - mcu_step_cb(); - else - mcu_step_reset_cb(); - resetstep = !resetstep; - mcu_enable_global_isr(); + // mcu_disable_global_isr(); + // static bool resetstep = false; + // if (!resetstep) + // mcu_step_cb(); + // else + // mcu_step_reset_cb(); + // resetstep = !resetstep; + // mcu_enable_global_isr(); + mcu_gen_step(); + mcu_gen_pwm(); } // static void mcu_uart_isr(void *arg) @@ -968,6 +1041,13 @@ void mcu_init(void) // init timer1 timer1_isr_init(); + timer1_attachInterrupt(mcu_itp_isr); + timer1_enable(TIM_DIV1, TIM_EDGE, TIM_LOOP); + timer1_write(625); + +// #ifndef RAM_ONLY_SETTINGS +// esp8266_eeprom_init(1024); // 1K Emulated EEPROM +// #endif } /** @@ -1122,10 +1202,12 @@ bool mcu_get_global_isr(void) void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { // up and down counter (generates half the step rate at each event) - uint32_t totalticks = (uint32_t)((float)(F_CPU >> 5) / frequency); + uint32_t totalticks = (uint32_t)((float)(128000UL >> 1) / frequency); + *prescaller = 0; while (totalticks > 0xFFFF) { - totalticks = 0xFFFF; + *prescaller++; + totalticks >>= 1; } *ticks = (uint16_t)totalticks; @@ -1136,9 +1218,8 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) * */ void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) { - timer1_attachInterrupt(mcu_itp_isr); - timer1_enable(TIM_DIV16, TIM_EDGE, TIM_LOOP); - timer1_write(ticks); + mcu_step_reload = (((uint32_t)ticks) << prescaller); + mcu_step_counter = mcu_step_reload; } /** @@ -1146,7 +1227,8 @@ void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) * */ void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller) { - timer1_write(ticks); + mcu_step_reload = (((uint32_t)ticks) << prescaller); + mcu_step_counter = mcu_step_reload; } /** @@ -1154,8 +1236,7 @@ void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller) * */ void mcu_stop_itp_isr(void) { - timer1_disable(); - timer1_detachInterrupt(); + mcu_step_reload = 0; } /** @@ -1206,7 +1287,11 @@ void mcu_dotasks(void) * */ uint8_t mcu_eeprom_getc(uint16_t address) { +// #ifndef RAM_ONLY_SETTINGS +// return esp8266_eeprom_read(address); +// #else return 0; +// #endif } /** @@ -1214,6 +1299,9 @@ uint8_t mcu_eeprom_getc(uint16_t address) * */ void mcu_eeprom_putc(uint16_t address, uint8_t value) { +// #ifndef RAM_ONLY_SETTINGS +// esp8266_eeprom_read(address, value); +// #endif } /** @@ -1221,6 +1309,9 @@ void mcu_eeprom_putc(uint16_t address, uint8_t value) * */ void mcu_eeprom_flush(void) { +// #ifndef RAM_ONLY_SETTINGS +// esp8266_eeprom_flush(); +// #endif } #endif diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 6de9e7efd..52fe32edd 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1111,8 +1111,8 @@ extern "C" #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) extern uint8_t esp8266_pwm[16]; -#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = Y) -#define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET]) +#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = (0x7F&(Y >> 1))) +#define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET] << 1) #define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) #ifdef __cplusplus diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index 3f8ac3b1a..59faa27cb 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -29,7 +29,7 @@ extern "C" #include #include -#define MCU_CALLBACK extern +#define MCU_CALLBACK // the extern is not necessary // this explicit declaration just serves to reeinforce the idea that these callbacks are implemented on other µCNC core code translation units From f1d697ed596be48c84d0b0b7df79dc5360c81446 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 27 Jun 2022 13:45:17 +0100 Subject: [PATCH 05/13] EEPROM emulation working --- uCNC/src/cnc_build.h | 4 +-- uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp | 9 +++-- uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 4 +-- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 35 ++++++++++++-------- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 6 ++-- 5 files changed, 34 insertions(+), 24 deletions(-) diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index 8a527f788..918c705ec 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -24,8 +24,8 @@ extern "C" { #endif -#define CNC_MAJOR_MINOR_VERSION "1.4" -#define CNC_PATCH_VERSION ".6pre" +#define CNC_MAJOR_MINOR_VERSION "1.5" +#define CNC_PATCH_VERSION ".beta" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp index 097da3e5b..b185c5354 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp @@ -11,9 +11,9 @@ extern "C" EEPROM.begin(size); } - void esp8266_eeprom_read(uint16_t address) + uint8_t esp8266_eeprom_read(uint16_t address) { - EEPROM.read(address); + return EEPROM.read(address); } void esp8266_eeprom_write(uint16_t address, uint8_t value) @@ -23,7 +23,10 @@ extern "C" void esp8266_eeprom_flush(void) { - EEPROM.commit(); + if (!EEPROM.commit()) + { + Serial.println("[MSG: EEPROM write error]"); + } } } diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp index d65447dd4..8f7aab016 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp @@ -89,11 +89,11 @@ bool esp8266_wifi_clientok(void) extern "C" { - void esp8266_com_init(void) + void esp8266_com_init(int baud) { #ifdef WIFI_DEBUG Serial.setRxBufferSize(1024); - Serial.begin(115200); + Serial.begin(baud); wifiManager.setDebugOutput(true); #else wifiManager.setDebugOutput(false); diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 88df639b3..059db1019 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -48,6 +48,13 @@ bool esp8266_com_rx_ready(void); bool esp8266_com_tx_ready(void); void esp8266_com_flush(void); +#ifndef RAM_ONLY_SETTINGS +void esp8266_eeprom_init(int size); +uint8_t esp8266_eeprom_read(uint16_t address); +void esp8266_eeprom_write(uint16_t address, uint8_t value); +void esp8266_eeprom_flush(void); +#endif + ETSTimer esp8266_rtc_timer; uint8_t esp8266_pwm[16]; @@ -361,7 +368,7 @@ IRAM_ATTR void mcu_itp_isr(void) // } // } -void mcu_usart_init(void) +static void mcu_usart_init(void) { esp8266_com_init(BAUDRATE); } @@ -1045,9 +1052,9 @@ void mcu_init(void) timer1_enable(TIM_DIV1, TIM_EDGE, TIM_LOOP); timer1_write(625); -// #ifndef RAM_ONLY_SETTINGS -// esp8266_eeprom_init(1024); // 1K Emulated EEPROM -// #endif +#ifndef RAM_ONLY_SETTINGS + esp8266_eeprom_init(1024); // 1K Emulated EEPROM +#endif } /** @@ -1287,11 +1294,11 @@ void mcu_dotasks(void) * */ uint8_t mcu_eeprom_getc(uint16_t address) { -// #ifndef RAM_ONLY_SETTINGS -// return esp8266_eeprom_read(address); -// #else +#ifndef RAM_ONLY_SETTINGS + return esp8266_eeprom_read(address); +#else return 0; -// #endif +#endif } /** @@ -1299,9 +1306,9 @@ uint8_t mcu_eeprom_getc(uint16_t address) * */ void mcu_eeprom_putc(uint16_t address, uint8_t value) { -// #ifndef RAM_ONLY_SETTINGS -// esp8266_eeprom_read(address, value); -// #endif +#ifndef RAM_ONLY_SETTINGS + esp8266_eeprom_write(address, value); +#endif } /** @@ -1309,9 +1316,9 @@ void mcu_eeprom_putc(uint16_t address, uint8_t value) * */ void mcu_eeprom_flush(void) { -// #ifndef RAM_ONLY_SETTINGS -// esp8266_eeprom_flush(); -// #endif +#ifndef RAM_ONLY_SETTINGS + esp8266_eeprom_flush(); +#endif } #endif diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 52fe32edd..85980c12a 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -43,7 +43,7 @@ extern "C" #endif // defines the maximum and minimum step rates #ifndef F_STEP_MAX -#define F_STEP_MAX 100000 +#define F_STEP_MAX 64000 #endif #ifndef F_STEP_MIN #define F_STEP_MIN 1 @@ -1081,7 +1081,7 @@ extern "C" #define DIO89_ISRCALLBACK __indirect__(X, ISRCALLBACK) #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifndef COM_PORT #define COM_PORT 0 #endif @@ -1111,7 +1111,7 @@ extern "C" #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) extern uint8_t esp8266_pwm[16]; -#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = (0x7F&(Y >> 1))) +#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = (0x7F & (Y >> 1))) #define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET] << 1) #define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) From eab3290bbb089dda67a1b29ea6a9e44249a9eb3a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 27 Jun 2022 14:36:41 +0100 Subject: [PATCH 06/13] Fixed platformio.ini --- platformio.ini | 6 ------ 1 file changed, 6 deletions(-) diff --git a/platformio.ini b/platformio.ini index c237c90d1..8615be5d4 100644 --- a/platformio.ini +++ b/platformio.ini @@ -89,12 +89,6 @@ board = blackpill_f401cc framework = arduino build_flags = -D BOARD=BOARD_BLACKPILL -D INTERFACE=1 -D HAL_TIM_MODULE_DISABLED -D HAL_EXTI_MODULE_DISABLED -fdata-sections -ffunction-sections -Wl,--gc-sections -[env:re_arm] -platform = nxplpc -board = lpc1768 -framework = mbed -build_flags = -D BOARD=BOARD_RE_ARM -D INTERFACE=1 -fdata-sections -ffunction-sections -Wl,--gc-sections - [env:d1] platform = espressif8266 framework = arduino From 2c6d639c02ac1e3520f3f2a3cad08acb5d111008 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 28 Jun 2022 20:38:15 +0100 Subject: [PATCH 07/13] fixed compilation for other processors --- platformio.ini | 2 +- uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp | 3 ++- uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp | 2 ++ uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 3 ++- 4 files changed, 7 insertions(+), 3 deletions(-) diff --git a/platformio.ini b/platformio.ini index 8615be5d4..818049300 100644 --- a/platformio.ini +++ b/platformio.ini @@ -95,4 +95,4 @@ framework = arduino board = d1 lib_deps = tzapu/WiFiManager -build_flags = -I include -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections +build_flags = -I include -D ESP8266 -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp index b185c5354..6a48d040c 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_eeprom.cpp @@ -1,5 +1,5 @@ #include "../../../../cnc_config.h" - +#ifdef ESP8266 #ifndef RAM_ONLY_SETTINGS #include #include @@ -30,4 +30,5 @@ extern "C" } } +#endif #endif \ No newline at end of file diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp index a37ead911..6ba73b349 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp @@ -17,6 +17,7 @@ */ #include "../../../../cnc_config.h" +#ifdef ESP8266 #include #include @@ -56,3 +57,4 @@ extern "C" } #endif +#endif diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp index 8f7aab016..2081432ba 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp @@ -17,7 +17,7 @@ See the GNU General Public License for more details. */ #include "../../../../cnc_config.h" - +#ifdef ESP8266 #if (INTERFACE == INTERFACE_WIFI) #include #include @@ -195,3 +195,4 @@ extern "C" } #endif +#endif From e9085d715f849d2b00b72984eee471b89be2e562 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 29 Jun 2022 12:05:49 +0100 Subject: [PATCH 08/13] Working with both UART and WIFI -modified INTERFACE NAME -UART and WiFi working in parallel. If no client present fall back to UART. --- platformio.ini | 2 +- uCNC/cnc_config.h | 9 ++- .../hal/boards/esp8266/boardmap_wemos_d1.h | 2 +- uCNC/src/hal/boards/samd21/boardmap_mzero.h | 2 +- uCNC/src/hal/boards/samd21/boardmap_zero.h | 2 +- .../src/hal/boards/stm32/boardmap_blackpill.h | 2 +- uCNC/src/hal/boards/stm32/boardmap_bluepill.h | 2 +- uCNC/src/hal/mcus/avr/mcumap_avr.h | 2 +- uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp | 14 ++-- uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 24 +++--- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 76 +++++++++++++++---- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 2 - uCNC/src/hal/mcus/samd21/mcu_samd21.c | 8 +- uCNC/src/hal/mcus/samd21/mcumap_samd21.h | 2 +- uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 10 +-- uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h | 4 +- uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 10 +-- uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h | 4 +- 18 files changed, 116 insertions(+), 61 deletions(-) diff --git a/platformio.ini b/platformio.ini index 818049300..8615be5d4 100644 --- a/platformio.ini +++ b/platformio.ini @@ -95,4 +95,4 @@ framework = arduino board = d1 lib_deps = tzapu/WiFiManager -build_flags = -I include -D ESP8266 -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections +build_flags = -I include -D BOARD=BOARD_WEMOS_D1 -D INTERFACE=0 -fdata-sections -ffunction-sections -Wl,--gc-sections diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index c25fe7766..e7bbdaefb 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -25,9 +25,8 @@ extern "C" { #endif -#define INTERFACE_USART 0 +#define INTERFACE_UART 0 #define INTERFACE_USB 1 -#define INTERFACE_WIFI 2 /** * Serial COM @@ -40,7 +39,11 @@ extern "C" #endif #ifndef INTERFACE -#define INTERFACE INTERFACE_USART +#define INTERFACE INTERFACE_UART +#endif + +#ifndef ENABLE_WIFI +#define ENABLE_WIFI #endif /** diff --git a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h index 850ec12f0..7fa91566a 100644 --- a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h +++ b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h @@ -51,7 +51,7 @@ extern "C" //#define ESTOP_ISR // Setup com pins -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define RX_BIT 3 #define TX_BIT 1 #define RX_PORT D diff --git a/uCNC/src/hal/boards/samd21/boardmap_mzero.h b/uCNC/src/hal/boards/samd21/boardmap_mzero.h index 21f63c95a..dddf461f9 100644 --- a/uCNC/src/hal/boards/samd21/boardmap_mzero.h +++ b/uCNC/src/hal/boards/samd21/boardmap_mzero.h @@ -84,7 +84,7 @@ extern "C" // #define CS_RES_ISR // On the STM32 always use sync TX UART (async doesn't work well) -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define COM_PORT 1 #define TX_BIT 10 #define TX_PORT A diff --git a/uCNC/src/hal/boards/samd21/boardmap_zero.h b/uCNC/src/hal/boards/samd21/boardmap_zero.h index efa914a48..2eb436176 100644 --- a/uCNC/src/hal/boards/samd21/boardmap_zero.h +++ b/uCNC/src/hal/boards/samd21/boardmap_zero.h @@ -84,7 +84,7 @@ extern "C" // #define CS_RES_ISR // On the STM32 always use sync TX UART (async doesn't work well) -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define COM_PORT 1 #define TX_BIT 10 #define TX_PORT A diff --git a/uCNC/src/hal/boards/stm32/boardmap_blackpill.h b/uCNC/src/hal/boards/stm32/boardmap_blackpill.h index b0d5c79eb..56771bb7a 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_blackpill.h +++ b/uCNC/src/hal/boards/stm32/boardmap_blackpill.h @@ -96,7 +96,7 @@ extern "C" #define SAFETY_DOOR_ISR // On the STM32 always use sync TX UART (async doesn't work well) -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define COM_PORT 1 #define TX_BIT 9 #define TX_PORT A diff --git a/uCNC/src/hal/boards/stm32/boardmap_bluepill.h b/uCNC/src/hal/boards/stm32/boardmap_bluepill.h index f0b8954b9..fd280a930 100644 --- a/uCNC/src/hal/boards/stm32/boardmap_bluepill.h +++ b/uCNC/src/hal/boards/stm32/boardmap_bluepill.h @@ -96,7 +96,7 @@ extern "C" #define SAFETY_DOOR_ISR // On the STM32 always use sync TX UART (async doesn't work well) -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define COM_PORT 1 #define TX_BIT 9 #define TX_PORT A diff --git a/uCNC/src/hal/mcus/avr/mcumap_avr.h b/uCNC/src/hal/mcus/avr/mcumap_avr.h index 138f12e68..023d80c51 100644 --- a/uCNC/src/hal/mcus/avr/mcumap_avr.h +++ b/uCNC/src/hal/mcus/avr/mcumap_avr.h @@ -4243,7 +4243,7 @@ extern "C" #endif // COM registers -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifndef COM_NUMBER #define COM_RX_vect USART_RX_vect #define COM_TX_vect USART_UDRE_vect diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp index 6ba73b349..040baf502 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp @@ -21,36 +21,36 @@ #include #include -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) extern "C" { - void esp8266_com_init(int baud) + void esp8266_uart_init(int baud) { Serial.begin(baud); } - char esp8266_com_read(void) + char esp8266_uart_read(void) { return Serial.read(); } - void esp8266_com_write(char c) + void esp8266_uart_write(char c) { Serial.write(c); } - bool esp8266_com_rx_ready(void) + bool esp8266_uart_rx_ready(void) { return (Serial.available() != 0); } - bool esp8266_com_tx_ready(void) + bool esp8266_uart_tx_ready(void) { return (Serial.availableForWrite() != 0); } - void esp8266_com_flush(void) + void esp8266_uart_flush(void) { Serial.flush(); } diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp index 2081432ba..69a00c2dd 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp @@ -18,7 +18,7 @@ See the GNU General Public License for more details. #include "../../../../cnc_config.h" #ifdef ESP8266 -#if (INTERFACE == INTERFACE_WIFI) +#ifdef ENABLE_WIFI #include #include #include @@ -64,13 +64,19 @@ typedef struct wifi_rxbuffer_ static wifi_rxbuffer_t wifi_rx_buffer; static wifi_rxbuffer_t wifi_tx_buffer; -bool esp8266_wifi_clientok(void) +extern "C" +{ + bool esp8266_wifi_clientok(void) { if (server.hasClient()) { if (serverClient && serverClient.connected()) { serverClient.stop(); + //flushes serial + while(Serial.available()){ + Serial.read(); + } } serverClient = server.available(); #ifdef WIFI_DEBUG @@ -87,9 +93,7 @@ bool esp8266_wifi_clientok(void) return false; } -extern "C" -{ - void esp8266_com_init(int baud) + void esp8266_wifi_init(int baud) { #ifdef WIFI_DEBUG Serial.setRxBufferSize(1024); @@ -118,7 +122,7 @@ extern "C" wifi_tx_buffer.current = 0; } - char esp8266_com_read(void) + char esp8266_wifi_read(void) { if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) { @@ -140,7 +144,7 @@ extern "C" return 0; } - void esp8266_com_write(char c) + void esp8266_wifi_write(char c) { if (esp8266_wifi_clientok()) { @@ -155,7 +159,7 @@ extern "C" } } - bool esp8266_com_rx_ready(void) + bool esp8266_wifi_rx_ready(void) { if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) { @@ -170,7 +174,7 @@ extern "C" return false; } - bool esp8266_com_tx_ready(void) + bool esp8266_wifi_tx_ready(void) { if (esp8266_wifi_clientok()) { @@ -183,7 +187,7 @@ extern "C" return false; } - void esp8266_com_flush(void) + void esp8266_wifi_flush(void) { if (esp8266_wifi_clientok()) { diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 059db1019..5bd26a1b3 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -41,12 +41,22 @@ static volatile bool esp8266_global_isr_enabled; static volatile uint32_t mcu_runtime_ms; -void esp8266_com_init(int baud); -char esp8266_com_read(void); -void esp8266_com_write(char c); -bool esp8266_com_rx_ready(void); -bool esp8266_com_tx_ready(void); -void esp8266_com_flush(void); +void esp8266_uart_init(int baud); +char esp8266_uart_read(void); +void esp8266_uart_write(char c); +bool esp8266_uart_rx_ready(void); +bool esp8266_uart_tx_ready(void); +void esp8266_uart_flush(void); + +#ifdef ENABLE_WIFI +void esp8266_wifi_init(int baud); +char esp8266_wifi_read(void); +void esp8266_wifi_write(char c); +bool esp8266_wifi_rx_ready(void); +bool esp8266_wifi_tx_ready(void); +void esp8266_wifi_flush(void); +bool esp8266_wifi_clientok(void); +#endif #ifndef RAM_ONLY_SETTINGS void esp8266_eeprom_init(int size); @@ -370,7 +380,10 @@ IRAM_ATTR void mcu_itp_isr(void) static void mcu_usart_init(void) { - esp8266_com_init(BAUDRATE); + esp8266_uart_init(BAUDRATE); +#ifdef ENABLE_WIFI + esp8266_wifi_init(BAUDRATE); +#endif } /** * initializes the mcu @@ -1115,7 +1128,18 @@ uint8_t mcu_get_pwm(uint8_t pwm) #ifndef mcu_tx_ready bool mcu_tx_ready(void) { - return esp8266_com_tx_ready(); +#ifdef ENABLE_WIFI + if (esp8266_wifi_clientok()) + { + return (esp8266_uart_tx_ready() && esp8266_wifi_tx_ready()); + } + else + { + return esp8266_uart_tx_ready(); + } +#else + return esp8266_uart_tx_ready(); +#endif } #endif @@ -1125,7 +1149,18 @@ bool mcu_tx_ready(void) #ifndef mcu_rx_ready bool mcu_rx_ready(void) { - return esp8266_com_rx_ready(); +#ifdef ENABLE_WIFI + if (esp8266_wifi_clientok()) + { + return (esp8266_wifi_rx_ready()); + } + else + { + return (esp8266_uart_rx_ready()); + } +#else + return esp8266_uart_rx_ready(); +#endif } #endif @@ -1144,7 +1179,10 @@ void mcu_putc(char c) while (!mcu_tx_ready()) ; #endif - esp8266_com_write(c); + esp8266_uart_write(c); +#ifdef ENABLE_WIFI + esp8266_wifi_write(c); +#endif } #endif @@ -1162,7 +1200,19 @@ char mcu_getc(void) while (!mcu_rx_ready()) ; #endif - return esp8266_com_read(); + +#ifdef ENABLE_WIFI + if (esp8266_wifi_clientok()) + { + return esp8266_wifi_read(); + } + else + { + return esp8266_uart_read(); + } +#else + return esp8266_uart_read(); +#endif } #endif @@ -1213,7 +1263,7 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) *prescaller = 0; while (totalticks > 0xFFFF) { - *prescaller++; + (*prescaller)+=1; totalticks >>= 1; } @@ -1277,7 +1327,7 @@ void mcu_dotasks(void) system_soft_wdt_feed(); #if (defined(ENABLE_SYNC_TX) || defined(ENABLE_SYNC_RX)) - esp8266_com_flush(); + esp8266_uart_flush(); #endif #ifdef ENABLE_SYNC_RX while (mcu_rx_ready()) diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 85980c12a..2a6ffe0ba 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1089,8 +1089,6 @@ extern "C" #define ENABLE_SYNC_RX #define ENABLE_SYNC_TX -#define mcu_tx_ready esp8266_com_tx_ready -#define mcu_rx_ready esp8266_com_rx_ready // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index 154482d49..9c9944f1b 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -207,7 +207,7 @@ void MCU_ITP_ISR(void) mcu_enable_global_isr(); } -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) void mcu_com_isr() { mcu_disable_global_isr(); @@ -232,7 +232,7 @@ void mcu_com_isr() void mcu_usart_init(void) { -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) PM->APBCMASK.reg |= PM_APBCMASK_COM; /* Setup GCLK SERCOMx to use GENCLK0 */ @@ -1322,7 +1322,7 @@ void mcu_putc(char c) tud_cdc_write_flush(); } #else -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_TX while (!mcu_tx_ready()) ; @@ -1354,7 +1354,7 @@ char mcu_getc(void) return (unsigned char)tud_cdc_read_char(); #else -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_RX while (!mcu_rx_ready()) ; diff --git a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h index b7c778161..68b13561d 100644 --- a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h +++ b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h @@ -2770,7 +2770,7 @@ extern "C" } #define mcu_get_global_isr() samd21_global_isr_enabled -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define mcu_rx_ready() (COM->USART.INTFLAG.bit.RXC) #define mcu_tx_ready() (COM->USART.INTFLAG.bit.DRE) #elif (INTERFACE == INTERFACE_USB) diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index a9b3f3a77..7af42a66a 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -135,7 +135,7 @@ volatile bool stm32_global_isr_enabled; * The isr functions * The respective IRQHandler will execute these functions **/ -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) void MCU_SERIAL_ISR(void) { mcu_disable_global_isr(); @@ -415,7 +415,7 @@ void osSystickHandler(void) static void mcu_rtc_init(void); static void mcu_usart_init(void); -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define APB2_PRESCALER RCC_CFGR_PPRE2_DIV2 #else #define APB2_PRESCALER RCC_CFGR_PPRE2_DIV1 @@ -464,7 +464,7 @@ void mcu_clocks_init() void mcu_usart_init(void) { -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) /*enables RCC clocks and GPIO*/ mcu_config_output_af(TX, GPIO_OUTALT_OD_50MHZ); mcu_config_input_af(RX); @@ -528,7 +528,7 @@ void mcu_putc(char c) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_TX while (!(COM_USART->SR & USART_SR_TC)) ; @@ -1255,7 +1255,7 @@ char mcu_getc(void) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_RX while (!(COM_USART->SR & USART_SR_RXNE)) ; diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index 6a07d4450..2d79a3fc6 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -4106,7 +4106,7 @@ extern "C" #endif // COM registers -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) // this MCU does not work well with both TX and RX interrupt // this forces the sync TX method to fix communication // #define ENABLE_SYNC_TX @@ -4307,7 +4307,7 @@ extern "C" // #define mcu_enable_tx_isr() // #define mcu_disable_tx_isr() // #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define mcu_rx_ready() (COM_USART->SR & USART_SR_RXNE) #define mcu_tx_ready() (COM_USART->SR & USART_SR_TXE) #elif (INTERFACE == INTERFACE_USB) diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index e6e2ce0c9..05cb88b2a 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -135,7 +135,7 @@ volatile bool stm32_global_isr_enabled; * The isr functions * The respective IRQHandler will execute these functions **/ -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) void MCU_SERIAL_ISR(void) { mcu_disable_global_isr(); @@ -402,7 +402,7 @@ void osSystickHandler(void) static void mcu_rtc_init(void); static void mcu_usart_init(void); -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define APB2_PRESCALER RCC_CFGR_PPRE2_DIV2 #else #define APB2_PRESCALER RCC_CFGR_PPRE2_DIV1 @@ -473,7 +473,7 @@ void mcu_clocks_init() void mcu_usart_init(void) { -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) /*enables RCC clocks and GPIO*/ RCC->COM_APB |= (COM_APBEN); mcu_config_af(TX, GPIO_AF_USART); @@ -550,7 +550,7 @@ void mcu_putc(char c) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_TX while (!(COM_USART->SR & USART_SR_TC)) ; @@ -1339,7 +1339,7 @@ char mcu_getc(void) #if !(LED < 0) mcu_toggle_output(LED); #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #ifdef ENABLE_SYNC_RX while (!(COM_USART->SR & USART_SR_RXNE)) ; diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index 8ec133c72..dab49d465 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -2922,7 +2922,7 @@ extern "C" #endif // COM registers -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) // this MCU does not work well with both TX and RX interrupt // this forces the sync TX method to fix communication // #define ENABLE_SYNC_TX @@ -3102,7 +3102,7 @@ extern "C" // #define mcu_enable_tx_isr() // #define mcu_disable_tx_isr() // #endif -#if (INTERFACE == INTERFACE_USART) +#if (INTERFACE == INTERFACE_UART) #define mcu_rx_ready() (COM_USART->SR & USART_SR_RXNE) #define mcu_tx_ready() (COM_USART->SR & USART_SR_TXE) #elif (INTERFACE == INTERFACE_USB) From fa357ff8e99ab7ddb223e3a8ea4ae86f17a523a6 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 28 Jul 2022 12:22:21 +0100 Subject: [PATCH 09/13] Unified WiFi/Uart functions -Unified WiFi/Uart functions -Fixed compilation for PIO --- platformio.ini | 1 + uCNC/cnc_config.h | 2 +- uCNC/src/hal/boards/esp8266/esp8266.ini | 14 ++ uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp | 155 +++++++++++++++- uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp | 202 --------------------- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 65 +------ uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 2 +- 7 files changed, 166 insertions(+), 275 deletions(-) create mode 100644 uCNC/src/hal/boards/esp8266/esp8266.ini delete mode 100644 uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp diff --git a/platformio.ini b/platformio.ini index 3f42234a4..90546e361 100644 --- a/platformio.ini +++ b/platformio.ini @@ -16,6 +16,7 @@ extra_configs = uCNC/src/hal/boards/avr/avr.ini uCNC/src/hal/boards/samd21/samd21.ini uCNC/src/hal/boards/stm32/stm32.ini + uCNC/src/hal/boards/esp8266/esp8266.ini ; uCNC/src/hal/mcus/virtual/virtual.ini [common] diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index e7bbdaefb..c1adf4e99 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -43,7 +43,7 @@ extern "C" #endif #ifndef ENABLE_WIFI -#define ENABLE_WIFI +// #define ENsABLE_WIFI #endif /** diff --git a/uCNC/src/hal/boards/esp8266/esp8266.ini b/uCNC/src/hal/boards/esp8266/esp8266.ini new file mode 100644 index 000000000..f35790575 --- /dev/null +++ b/uCNC/src/hal/boards/esp8266/esp8266.ini @@ -0,0 +1,14 @@ +################ +# STM32 Boards # +################ + +[env:d1] +platform = espressif8266 +framework = arduino +board = d1 +build_src_filter = +<*>- +lib_deps = + https://github.com/tzapu/WiFiManager/archive/refs/heads/master.zip +build_flags = -DBOARD=BOARD_WEMOS_D1 -DINTERFACE=0 -DENABLE_WIFI +upload_speed = 256000 +board_build.f_cpu = 160000000L diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp index 040baf502..e590bfd79 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_uart.cpp @@ -4,7 +4,7 @@ Copyright: Copyright (c) João Martins Author: João Martins - Date: 24-06-2022 + Date: 27-07-2022 µCNC is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -17,44 +17,179 @@ */ #include "../../../../cnc_config.h" +#include "../mcu.h" #ifdef ESP8266 #include +#include #include -#if (INTERFACE == INTERFACE_UART) +#ifdef ENABLE_WIFI +#include +#include +#include +#include +#include +#include + +#ifndef WIFI_PORT +#define WIFI_PORT 23 +#endif + +#ifndef WIFI_USER +#define WIFI_USER "admin" +#endif + +#ifndef WIFI_PASS +#define WIFI_PASS "pass" +#endif + +ESP8266WebServer httpServer(80); +ESP8266HTTPUpdateServer httpUpdater; +const char *update_path = "/firmware"; +const char *update_username = WIFI_USER; +const char *update_password = WIFI_PASS; +#define MAX_SRV_CLIENTS 1 +WiFiServer server(WIFI_PORT); +WiFiClient serverClient; +WiFiManager wifiManager; +#endif + +#ifndef ESP8266_BUFFER_SIZE +#define ESP8266_BUFFER_SIZE 255 +#endif + +static char esp8266_tx_buffer[ESP8266_BUFFER_SIZE]; +static uint8_t esp8266_tx_buffer_counter; extern "C" { + bool esp8266_wifi_clientok(void) + { + if (server.hasClient()) + { + if (serverClient) + { + if (serverClient.connected()) + { + serverClient.stop(); + } + } + serverClient = server.available(); + serverClient.println("[MSG: New client connected]\r\n"); + return false; + } + else if (serverClient) + { + if (serverClient.connected()) + { + return true; + } + } + + return false; + } + void esp8266_uart_init(int baud) { Serial.begin(baud); +#ifdef WIFI_DEBUG + wifiManager.setDebugOutput(true); +#else + wifiManager.setDebugOutput(false); +#endif + wifiManager.setConfigPortalBlocking(false); + wifiManager.setConfigPortalTimeout(30); + if (!wifiManager.autoConnect("ESP8266")) + { + Serial.println("[MSG: WiFi manager up]"); + Serial.println("[MSG: Setup page @ 192.168.4.1]"); + } + + server.begin(); + server.setNoDelay(true); + httpUpdater.setup(&httpServer, update_path, update_username, update_password); + httpServer.begin(); + WiFi.setSleepMode(WIFI_NONE_SLEEP); + + esp8266_tx_buffer_counter = 0; + } + + void esp8266_uart_flush(void) + { + Serial.println(esp8266_tx_buffer); + Serial.flush(); + if (esp8266_wifi_clientok()) + { + serverClient.println(esp8266_tx_buffer); + serverClient.flush(); + } + esp8266_tx_buffer_counter = 0; } - char esp8266_uart_read(void) + unsigned char esp8266_uart_read(void) { - return Serial.read(); + return (unsigned char)Serial.read(); } void esp8266_uart_write(char c) { - Serial.write(c); + switch (c) + { + case '\n': + case '\r': + if (esp8266_tx_buffer_counter) + { + esp8266_tx_buffer[esp8266_tx_buffer_counter] = 0; + esp8266_uart_flush(); + } + break; + default: + if (esp8266_tx_buffer_counter >= (ESP8266_BUFFER_SIZE - 1)) + { + esp8266_tx_buffer[esp8266_tx_buffer_counter] = 0; + esp8266_uart_flush(); + } + + esp8266_tx_buffer[esp8266_tx_buffer_counter++] = c; + break; + } } bool esp8266_uart_rx_ready(void) { - return (Serial.available() != 0); + bool wifiready = false; + if (esp8266_wifi_clientok()) + { + wifiready = (serverClient.available() > 0); + } + + return ((Serial.available() > 0) || wifiready); } bool esp8266_uart_tx_ready(void) { - return (Serial.availableForWrite() != 0); + return (esp8266_tx_buffer_counter != ESP8266_BUFFER_SIZE); } - void esp8266_uart_flush(void) + void esp8266_uart_process(void) { - Serial.flush(); + while (Serial.available() > 0) + { + system_soft_wdt_feed(); + mcu_com_rx_cb((unsigned char)Serial.read()); + } + + wifiManager.process(); + httpServer.handleClient(); + if (esp8266_wifi_clientok()) + { + while (serverClient.available() > 0) + { + system_soft_wdt_feed(); + mcu_com_rx_cb((unsigned char)serverClient.read()); + } + } } } #endif -#endif diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp deleted file mode 100644 index 69a00c2dd..000000000 --- a/uCNC/src/hal/mcus/esp8266/esp8266_wifi.cpp +++ /dev/null @@ -1,202 +0,0 @@ -/* -Name: esp8266_wifi.cpp -Description: Contains all Arduino ESP8266 C++ to C functions used by WiFi in µCNC. - -Copyright: Copyright (c) João Martins -Author: João Martins -Date: 24-06-2022 - -µCNC is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. Please see - -µCNC is distributed WITHOUT ANY WARRANTY; -Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. -See the GNU General Public License for more details. -*/ - -#include "../../../../cnc_config.h" -#ifdef ESP8266 -#ifdef ENABLE_WIFI -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#ifndef WIFI_BUFFER_SIZE -#define WIFI_BUFFER_SIZE 255 -#endif - -#ifndef WIFI_PORT -#define WIFI_PORT 23 -#endif - -#ifndef WIFI_USER -#define WIFI_USER "admin" -#endif - -#ifndef WIFI_PASS -#define WIFI_PASS "pass" -#endif - -ESP8266WebServer httpServer(80); -ESP8266HTTPUpdateServer httpUpdater; -const char *update_path = "/firmware"; -const char *update_username = WIFI_USER; -const char *update_password = WIFI_PASS; -#define MAX_SRV_CLIENTS 1 -WiFiServer server(WIFI_PORT); -WiFiClient serverClient; -WiFiManager wifiManager; -typedef struct wifi_rxbuffer_ -{ - char buffer[WIFI_BUFFER_SIZE]; - uint8_t len; - uint8_t current; -} wifi_rxbuffer_t; - -static wifi_rxbuffer_t wifi_rx_buffer; -static wifi_rxbuffer_t wifi_tx_buffer; - -extern "C" -{ - bool esp8266_wifi_clientok(void) -{ - if (server.hasClient()) - { - if (serverClient && serverClient.connected()) - { - serverClient.stop(); - //flushes serial - while(Serial.available()){ - Serial.read(); - } - } - serverClient = server.available(); -#ifdef WIFI_DEBUG - Serial.println("[MSG: New client accepted]"); -#endif - serverClient.write("[MSG: New client connected]\r\n"); - return false; - } - else if (serverClient && serverClient.connected()) - { - return true; - } - - return false; -} - - void esp8266_wifi_init(int baud) - { -#ifdef WIFI_DEBUG - Serial.setRxBufferSize(1024); - Serial.begin(baud); - wifiManager.setDebugOutput(true); -#else - wifiManager.setDebugOutput(false); -#endif - wifiManager.autoConnect("ESP8266"); -#ifdef WIFI_DEBUG - Serial.println("[MSG: WiFi manager up]"); - Serial.println("[MSG: Setup page @ 192.168.4.1]"); -#endif - server.begin(); - server.setNoDelay(true); - httpUpdater.setup(&httpServer, update_path, update_username, update_password); - httpServer.begin(); - WiFi.setSleepMode(WIFI_NONE_SLEEP); - - memset(wifi_rx_buffer.buffer, 0, WIFI_BUFFER_SIZE); - wifi_rx_buffer.len = 0; - wifi_rx_buffer.current = 0; - - memset(wifi_tx_buffer.buffer, 0, WIFI_BUFFER_SIZE); - wifi_tx_buffer.len = 0; - wifi_tx_buffer.current = 0; - } - - char esp8266_wifi_read(void) - { - if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) - { - return wifi_rx_buffer.buffer[wifi_rx_buffer.current++]; - } - - if (esp8266_wifi_clientok()) - { - size_t rxlen = serverClient.available(); - if (rxlen > 0) - { - serverClient.readBytes(wifi_rx_buffer.buffer, rxlen); - wifi_rx_buffer.len = rxlen; - wifi_rx_buffer.current = 1; - return wifi_rx_buffer.buffer[0]; - } - } - - return 0; - } - - void esp8266_wifi_write(char c) - { - if (esp8266_wifi_clientok()) - { - wifi_tx_buffer.buffer[wifi_tx_buffer.len] = c; - wifi_tx_buffer.len++; - if (c == '\n') - { - serverClient.write(wifi_tx_buffer.buffer, (size_t)wifi_tx_buffer.len); - memset(wifi_tx_buffer.buffer, 0, WIFI_BUFFER_SIZE); - wifi_tx_buffer.len = 0; - } - } - } - - bool esp8266_wifi_rx_ready(void) - { - if (wifi_rx_buffer.len != 0 && wifi_rx_buffer.len > wifi_rx_buffer.current) - { - return true; - } - - if (esp8266_wifi_clientok()) - { - return (serverClient.available() != 0); - } - - return false; - } - - bool esp8266_wifi_tx_ready(void) - { - if (esp8266_wifi_clientok()) - { - if (wifi_tx_buffer.len < WIFI_BUFFER_SIZE) - { - return true; - } - } - - return false; - } - - void esp8266_wifi_flush(void) - { - if (esp8266_wifi_clientok()) - { - serverClient.flush(); - } - - httpServer.handleClient(); - } -} - -#endif -#endif diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 5bd26a1b3..38586d9ad 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -47,16 +47,7 @@ void esp8266_uart_write(char c); bool esp8266_uart_rx_ready(void); bool esp8266_uart_tx_ready(void); void esp8266_uart_flush(void); - -#ifdef ENABLE_WIFI -void esp8266_wifi_init(int baud); -char esp8266_wifi_read(void); -void esp8266_wifi_write(char c); -bool esp8266_wifi_rx_ready(void); -bool esp8266_wifi_tx_ready(void); -void esp8266_wifi_flush(void); -bool esp8266_wifi_clientok(void); -#endif +void esp8266_uart_process(void); #ifndef RAM_ONLY_SETTINGS void esp8266_eeprom_init(int size); @@ -381,9 +372,6 @@ IRAM_ATTR void mcu_itp_isr(void) static void mcu_usart_init(void) { esp8266_uart_init(BAUDRATE); -#ifdef ENABLE_WIFI - esp8266_wifi_init(BAUDRATE); -#endif } /** * initializes the mcu @@ -1128,18 +1116,7 @@ uint8_t mcu_get_pwm(uint8_t pwm) #ifndef mcu_tx_ready bool mcu_tx_ready(void) { -#ifdef ENABLE_WIFI - if (esp8266_wifi_clientok()) - { - return (esp8266_uart_tx_ready() && esp8266_wifi_tx_ready()); - } - else - { - return esp8266_uart_tx_ready(); - } -#else return esp8266_uart_tx_ready(); -#endif } #endif @@ -1149,18 +1126,7 @@ bool mcu_tx_ready(void) #ifndef mcu_rx_ready bool mcu_rx_ready(void) { -#ifdef ENABLE_WIFI - if (esp8266_wifi_clientok()) - { - return (esp8266_wifi_rx_ready()); - } - else - { - return (esp8266_uart_rx_ready()); - } -#else return esp8266_uart_rx_ready(); -#endif } #endif @@ -1179,10 +1145,8 @@ void mcu_putc(char c) while (!mcu_tx_ready()) ; #endif + esp8266_uart_write(c); -#ifdef ENABLE_WIFI - esp8266_wifi_write(c); -#endif } #endif @@ -1201,18 +1165,7 @@ char mcu_getc(void) ; #endif -#ifdef ENABLE_WIFI - if (esp8266_wifi_clientok()) - { - return esp8266_wifi_read(); - } - else - { - return esp8266_uart_read(); - } -#else return esp8266_uart_read(); -#endif } #endif @@ -1263,7 +1216,7 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) *prescaller = 0; while (totalticks > 0xFFFF) { - (*prescaller)+=1; + (*prescaller) += 1; totalticks >>= 1; } @@ -1325,17 +1278,7 @@ void mcu_dotasks(void) { // reset WDT system_soft_wdt_feed(); - -#if (defined(ENABLE_SYNC_TX) || defined(ENABLE_SYNC_RX)) - esp8266_uart_flush(); -#endif -#ifdef ENABLE_SYNC_RX - while (mcu_rx_ready()) - { - unsigned char c = mcu_getc(); - mcu_com_rx_cb(c); - } -#endif + esp8266_uart_process(); } // Non volatile memory diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 2a6ffe0ba..53eb8a703 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -39,7 +39,7 @@ extern "C" */ // defines the frequency of the mcu #ifndef F_CPU -#define F_CPU 80000000UL +#define F_CPU 80000000L #endif // defines the maximum and minimum step rates #ifndef F_STEP_MAX From 2b9d990325b840fb782d3302a88f846bae6e1c52 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 28 Jul 2022 12:31:38 +0100 Subject: [PATCH 10/13] fix typo --- uCNC/cnc_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index c1adf4e99..9b2b1d2c7 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -43,7 +43,7 @@ extern "C" #endif #ifndef ENABLE_WIFI -// #define ENsABLE_WIFI +// #define ENABLE_WIFI #endif /** From d19771adb99ea3280927e1d4aaaae855f5a5c4c2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Jul 2022 15:43:06 +0100 Subject: [PATCH 11/13] modified callback attributes - modified callback attributes - resizable RX buffer --- uCNC/src/cnc.c | 2 +- uCNC/src/core/interpolator.c | 4 ++-- uCNC/src/core/io_control.c | 8 +++---- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 19 ++++++++++++++++ uCNC/src/hal/mcus/mcu.h | 26 +++++++++++++++++----- uCNC/src/hal/mcus/virtual/mcu_virtual.c | 2 +- uCNC/src/interface/serial.c | 4 ++-- uCNC/src/interface/serial.h | 2 ++ 8 files changed, 51 insertions(+), 16 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index be22d42db..aab344e26 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -206,7 +206,7 @@ bool cnc_dotasks(void) } // this function is executed every millisecond -void mcu_rtc_cb(uint32_t millis) +MCU_CALLBACK void mcu_rtc_cb(uint32_t millis) { static bool running = false; diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index c08670f7e..1ab0a9e60 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1080,13 +1080,13 @@ uint32_t itp_get_rt_line_number(void) #endif // always fires after pulse -void mcu_step_reset_cb(void) +MCU_CALLBACK void mcu_step_reset_cb(void) { // always resets all stepper pins io_set_steps(g_settings.step_invert_mask); } -void mcu_step_cb(void) +MCU_CALLBACK void mcu_step_cb(void) { static uint8_t stepbits = 0; static bool itp_busy = false; diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 09ef45a03..4ef99a6a7 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -27,7 +27,7 @@ static volatile uint8_t io_spindle_speed; static uint8_t io_lock_limits_mask; static uint8_t io_invert_limits_mask; -void mcu_limits_changed_cb(void) +MCU_IO_CALLBACK void mcu_limits_changed_cb(void) { #ifndef DISABLE_ALL_LIMITS @@ -112,7 +112,7 @@ void mcu_limits_changed_cb(void) #endif } -void mcu_controls_changed_cb(void) +MCU_IO_CALLBACK void mcu_controls_changed_cb(void) { #ifdef DISABLE_ALL_CONTROLS return; @@ -157,7 +157,7 @@ void mcu_controls_changed_cb(void) #endif } -void mcu_probe_changed_cb(void) +MCU_IO_CALLBACK void mcu_probe_changed_cb(void) { #ifdef DISABLE_PROBE return; @@ -183,7 +183,7 @@ void mcu_probe_changed_cb(void) // overridable // for now if encoders are enabled this will be override by the encoder call -void __attribute__((weak)) mcu_inputs_changed_cb(void) +MCU_IO_CALLBACK void __attribute__((weak)) mcu_inputs_changed_cb(void) { #ifdef ENABLE_IO_MODULES mod_input_change_hook(); diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 53eb8a703..ee7d4685a 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -58,6 +58,25 @@ extern "C" #define rom_memcpy memcpy #define rom_read_byte * +#ifndef MCU_CALLBACK +#define MCU_CALLBACK IRAM_ATTR +#endif + +#ifdef ENABLE_RX_SYNC +#define MCU_RX_CALLBACK ICACHE_FLASH_ATTR +#endif + +#ifdef ENABLE_TX_SYNC +#define MCU_TX_CALLBACK ICACHE_FLASH_ATTR +#endif + +#define MCU_IO_CALLBACK ICACHE_FLASH_ATTR + +#ifdef RX_BUFFER_CAPACITY +#define RX_BUFFER_CAPACITY 255 +#endif + + #define __SIZEOF_FLOAT__ 4 // used by the parser diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index 59faa27cb..679500082 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -29,7 +29,21 @@ extern "C" #include #include +#ifndef MCU_CALLBACK #define MCU_CALLBACK +#endif + +#ifndef MCU_TX_CALLBACK +#define MCU_TX_CALLBACK MCU_CALLBACK +#endif + +#ifndef MCU_RX_CALLBACK +#define MCU_RX_CALLBACK MCU_CALLBACK +#endif + +#ifndef MCU_IO_CALLBACK +#define MCU_IO_CALLBACK MCU_CALLBACK +#endif // the extern is not necessary // this explicit declaration just serves to reeinforce the idea that these callbacks are implemented on other µCNC core code translation units @@ -37,13 +51,13 @@ extern "C" MCU_CALLBACK void mcu_step_cb(void); MCU_CALLBACK void mcu_step_reset_cb(void); - MCU_CALLBACK void mcu_com_rx_cb(unsigned char c); - MCU_CALLBACK void mcu_com_tx_cb(); + MCU_RX_CALLBACK void mcu_com_rx_cb(unsigned char c); + MCU_TX_CALLBACK void mcu_com_tx_cb(); MCU_CALLBACK void mcu_rtc_cb(uint32_t millis); - MCU_CALLBACK void mcu_controls_changed_cb(void); - MCU_CALLBACK void mcu_limits_changed_cb(void); - MCU_CALLBACK void mcu_probe_changed_cb(void); - MCU_CALLBACK void mcu_inputs_changed_cb(void); + MCU_IO_CALLBACK void mcu_controls_changed_cb(void); + MCU_IO_CALLBACK void mcu_limits_changed_cb(void); + MCU_IO_CALLBACK void mcu_probe_changed_cb(void); + MCU_IO_CALLBACK void mcu_inputs_changed_cb(void); /*IO functions*/ diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 7a25c4c7a..bef4083e0 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -84,7 +84,7 @@ #endif extern void mod_input_change_hook(void); -void mcu_inputs_changed_cb(void) +MCU_IO_CALLBACK void mcu_inputs_changed_cb(void) { #ifdef ENABLE_IO_MODULES mod_input_change_hook(); diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index da53d524d..2ee6d35af 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -348,7 +348,7 @@ void serial_flush(void) // ISR // New char handle strategy // All ascii will be sent to buffer and processed later (including comments) -void mcu_com_rx_cb(unsigned char c) +MCU_RX_CALLBACK void mcu_com_rx_cb(unsigned char c) { uint8_t write; if (c < ((unsigned char)'~')) // ascii (except CMD_CODE_CYCLE_START and DEL) @@ -389,7 +389,7 @@ void mcu_com_rx_cb(unsigned char c) } } -void mcu_com_tx_cb(void) +MCU_TX_CALLBACK void mcu_com_tx_cb(void) { #ifndef ENABLE_SYNC_TX uint8_t read = serial_tx_read; diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index e5fb59a7f..31f72e63f 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -31,7 +31,9 @@ extern "C" #define EOL 0x00 // end of line char #define OVF 0x2A // overflow char #define SAFEMARGIN 2 +#ifdef RX_BUFFER_CAPACITY #define RX_BUFFER_CAPACITY 128 +#endif #define RX_BUFFER_SIZE (RX_BUFFER_CAPACITY + SAFEMARGIN) // buffer sizes #ifndef ECHO_CMD #define TX_BUFFER_SIZE (112 + SAFEMARGIN) // buffer sizes From 5d9a222192c38c21e2ad832873571949a480cbec Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Jul 2022 15:51:02 +0100 Subject: [PATCH 12/13] fixed typo --- uCNC/src/interface/serial.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index 31f72e63f..022406860 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -31,7 +31,7 @@ extern "C" #define EOL 0x00 // end of line char #define OVF 0x2A // overflow char #define SAFEMARGIN 2 -#ifdef RX_BUFFER_CAPACITY +#ifndef RX_BUFFER_CAPACITY #define RX_BUFFER_CAPACITY 128 #endif #define RX_BUFFER_SIZE (RX_BUFFER_CAPACITY + SAFEMARGIN) // buffer sizes From 9b38efb4d7c175d1ce7adf646bf9270f221501c9 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Jul 2022 15:58:44 +0100 Subject: [PATCH 13/13] Update CHANGELOG.md --- CHANGELOG.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 33f9c4cf5..34786e2b6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -6,10 +6,11 @@ # Changelog -## [1.4.7] - Unreleased +## [1.5.b] - Unreleased ### Added +- added core support for ESP8266 with limitied functionalities (#222) - added Marlin M913 command to TMC driver module (#226) ### Changed @@ -19,6 +20,7 @@ - minor optimization with auto-report enabled (#230) - split platformio files for each board family (#231) - updated virtual HAL for Windows (#232) +- configurable RX serial buffer size (#222) ### Fixed @@ -926,7 +928,7 @@ Version 1.1.0 comes with many added features and improvements over the previous ### Initial release -[1.4.7]: https://github.com/Paciente8159/uCNC/releases/tag/v1.4.7 +[1.5.b]: https://github.com/Paciente8159/uCNC/releases/tag/v1.5.b [1.4.6]: https://github.com/Paciente8159/uCNC/releases/tag/v1.4.6 [1.4.5]: https://github.com/Paciente8159/uCNC/releases/tag/v1.4.5 [1.4.4]: https://github.com/Paciente8159/uCNC/releases/tag/v1.4.4