1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-21 13:52:23 +02:00

Fixed some includes. Fixed name conflict of LEDCPin. Added native stub implementations for x86 for the rest.

This commit is contained in:
Stefan de Bruijn
2021-08-03 10:21:40 +02:00
parent 44d0c3eca0
commit 169818e31e
47 changed files with 482 additions and 186 deletions

View File

@@ -17,11 +17,16 @@
*/ */
#include "Logging.h" #include "Logging.h"
#include "SettingsDefinitions.h"
#ifndef ESP32 #ifndef ESP32
# include <iostream> # include <iostream>
bool atMsgLevel(MsgLevel level) {
return message_level == nullptr || message_level->get() >= level;
}
DebugStream::DebugStream(const char* name) { DebugStream::DebugStream(const char* name) {
std::cout << "[MSG:" << name << ": "; std::cout << "[MSG:" << name << ": ";
} }
@@ -35,8 +40,6 @@ DebugStream::~DebugStream() {
#else #else
# include "SettingsDefinitions.h"
bool atMsgLevel(MsgLevel level) { bool atMsgLevel(MsgLevel level) {
return message_level == nullptr || message_level->get() >= level; return message_level == nullptr || message_level->get() >= level;
} }

View File

@@ -7,6 +7,8 @@
#include "../Limits.h" #include "../Limits.h"
#include "../System.h" // sys_rt_exec_alarm #include "../System.h" // sys_rt_exec_alarm
#include <esp32-hal-gpio.h> // CHANGE
namespace Machine { namespace Machine {
LimitPin::LimitPin(Pin& pin, int axis, int gang, int direction, bool& pHardLimits) : LimitPin::LimitPin(Pin& pin, int axis, int gang, int direction, bool& pHardLimits) :
_axis(axis), _gang(gang), _value(false), _pHardLimits(pHardLimits), _pin(pin) { _axis(axis), _gang(gang), _value(false), _pHardLimits(pHardLimits), _pin(pin) {

View File

@@ -1,6 +1,7 @@
#pragma once #pragma once
#include "../Pin.h" #include "../Pin.h"
#include <esp_attr.h> // IRAM_ATTR #include <esp_attr.h> // IRAM_ATTR
namespace Machine { namespace Machine {

View File

@@ -31,7 +31,7 @@
#include "RcServo.h" #include "RcServo.h"
#include "../Machine/MachineConfig.h" #include "../Machine/MachineConfig.h"
#include "../Pins/Ledc.h" #include "../Pins/LedcPin.h"
#include "../Pin.h" #include "../Pin.h"
#include "../Limits.h" // limitsMaxPosition #include "../Limits.h" // limitsMaxPosition
#include "RcServoSettings.h" #include "RcServoSettings.h"

View File

@@ -27,6 +27,8 @@
#include "../Stepper.h" // ST_I2S_* #include "../Stepper.h" // ST_I2S_*
#include "../Stepping.h" // config->_stepping->_engine #include "../Stepping.h" // config->_stepping->_engine
#include <esp32-hal-gpio.h> // gpio
using namespace Machine; using namespace Machine;
namespace Motors { namespace Motors {

View File

@@ -146,7 +146,9 @@ inline int32_t IRAM_ATTR usToEndTicks(int32_t us) {
inline void IRAM_ATTR spinUntil(int32_t endTicks) { inline void IRAM_ATTR spinUntil(int32_t endTicks) {
while ((XTHAL_GET_CCOUNT() - endTicks) < 0) { while ((XTHAL_GET_CCOUNT() - endTicks) < 0) {
#ifdef ESP32
asm volatile("nop"); asm volatile("nop");
#endif
} }
} }

View File

@@ -1,4 +1,4 @@
#include "Ledc.h" #include "LedcPin.h"
/* /*
Ledc.cpp Ledc.cpp

View File

@@ -26,7 +26,7 @@
*/ */
#include "10vSpindle.h" #include "10vSpindle.h"
#include "../Pins/Ledc.h" #include "../Pins/LedcPin.h"
#include "../System.h" // sys.spindle_speed #include "../System.h" // sys.spindle_speed
#include "../GCode.h" // gc_state.modal #include "../GCode.h" // gc_state.modal
#include <esp32-hal-ledc.h> // ledcDetachPin #include <esp32-hal-ledc.h> // ledcDetachPin

View File

@@ -32,7 +32,7 @@
*/ */
#include "BESCSpindle.h" #include "BESCSpindle.h"
#include "../Pins/Ledc.h" #include "../Pins/LedcPin.h"
#include <soc/ledc_struct.h> #include <soc/ledc_struct.h>

View File

@@ -24,7 +24,7 @@
#include "../System.h" // sys.report_ovr_counter #include "../System.h" // sys.report_ovr_counter
#include "../GCode.h" // gc_state.modal #include "../GCode.h" // gc_state.modal
#include "../Logging.h" #include "../Logging.h"
#include "../Pins/Ledc.h" #include "../Pins/LedcPin.h"
#include <esp32-hal-ledc.h> // ledcDetachPin #include <esp32-hal-ledc.h> // ledcDetachPin
// ======================= PWM ============================== // ======================= PWM ==============================

View File

@@ -31,6 +31,7 @@
#include <cstring> // memset #include <cstring> // memset
#include <freertos/queue.h> #include <freertos/queue.h>
#include <freertos/task.h> #include <freertos/task.h>
#include <esp32-hal-gpio.h> // LOW
// Declare system global variable structure // Declare system global variable structure
system_t sys; system_t sys;

View File

@@ -29,6 +29,7 @@
#include <soc/dport_reg.h> #include <soc/dport_reg.h>
#include <soc/rtc.h> #include <soc/rtc.h>
#include <driver/uart.h> #include <driver/uart.h>
#include <esp32-hal-gpio.h> // GPIO_NUM_1 etc
Uart::Uart() : _pushback(-1) { Uart::Uart() : _pushback(-1) {
static int currentNumber = 1; static int currentNumber = 1;

View File

@@ -1,6 +1,7 @@
#include "../TestFramework.h" #include "../TestFramework.h"
#include <src/Pin.h> #include <src/Pin.h>
#include <esp32-hal-gpio.h> // CHANGE
namespace Pins { namespace Pins {
Test(Error, Pins) { Test(Error, Pins) {

View File

@@ -1,6 +1,7 @@
#include "../TestFramework.h" #include "../TestFramework.h"
#include <src/Pin.h> #include <src/Pin.h>
#include <esp32-hal-gpio.h> // CHANGE
namespace Pins { namespace Pins {
Test(Undefined, Pins) { Test(Undefined, Pins) {

View File

@@ -83,6 +83,7 @@
<ClInclude Include="Grbl_Esp32\src\Machine\Gang.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\Gang.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\Homing.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\Homing.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\I2SOBus.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\I2SOBus.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\LimitPin.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\MachineConfig.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\MachineConfig.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\Macros.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\Macros.h" />
<ClInclude Include="Grbl_Esp32\src\Machine\SPIBus.h" /> <ClInclude Include="Grbl_Esp32\src\Machine\SPIBus.h" />
@@ -108,7 +109,7 @@
<ClInclude Include="Grbl_Esp32\src\Pins\ErrorPinDetail.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\ErrorPinDetail.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\GPIOPinDetail.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\GPIOPinDetail.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\I2SOPinDetail.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\I2SOPinDetail.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\Ledc.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\LedcPin.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\PinAttributes.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\PinAttributes.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\PinCapabilities.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\PinCapabilities.h" />
<ClInclude Include="Grbl_Esp32\src\Pins\PinDetail.h" /> <ClInclude Include="Grbl_Esp32\src\Pins\PinDetail.h" />
@@ -172,6 +173,15 @@
<ClInclude Include="X86TestSupport\driver\ledc.h" /> <ClInclude Include="X86TestSupport\driver\ledc.h" />
<ClInclude Include="X86TestSupport\driver\rmt.h" /> <ClInclude Include="X86TestSupport\driver\rmt.h" />
<ClInclude Include="X86TestSupport\driver\uart.h" /> <ClInclude Include="X86TestSupport\driver\uart.h" />
<ClInclude Include="X86TestSupport\Esp.h" />
<ClInclude Include="X86TestSupport\esp32-hal-cpu.h" />
<ClInclude Include="X86TestSupport\esp32-hal-dac.h" />
<ClInclude Include="X86TestSupport\esp32-hal-gpio.h" />
<ClInclude Include="X86TestSupport\esp32-hal-ledc.h" />
<ClInclude Include="X86TestSupport\esp32-hal-matrix.h" />
<ClInclude Include="X86TestSupport\esp32-hal-timer.h" />
<ClInclude Include="X86TestSupport\esp32-hal.h" />
<ClInclude Include="X86TestSupport\esp_attr.h" />
<ClInclude Include="X86TestSupport\esp_err.h" /> <ClInclude Include="X86TestSupport\esp_err.h" />
<ClInclude Include="X86TestSupport\esp_system.h" /> <ClInclude Include="X86TestSupport\esp_system.h" />
<ClInclude Include="X86TestSupport\freertos\FreeRTOS.h" /> <ClInclude Include="X86TestSupport\freertos\FreeRTOS.h" />
@@ -195,10 +205,10 @@
<ClInclude Include="X86TestSupport\SPI.h" /> <ClInclude Include="X86TestSupport\SPI.h" />
<ClInclude Include="X86TestSupport\SPIFFS.h" /> <ClInclude Include="X86TestSupport\SPIFFS.h" />
<ClInclude Include="X86TestSupport\Stream.h" /> <ClInclude Include="X86TestSupport\Stream.h" />
<ClInclude Include="X86TestSupport\TMCStepper.h" />
<ClInclude Include="X86TestSupport\TMC\TMCStepper.h" /> <ClInclude Include="X86TestSupport\TMC\TMCStepper.h" />
<ClInclude Include="X86TestSupport\TMC\TMCStepper_UTILITY.h" /> <ClInclude Include="X86TestSupport\TMC\TMCStepper_UTILITY.h" />
<ClInclude Include="X86TestSupport\WString.h" /> <ClInclude Include="X86TestSupport\WString.h" />
<ClInclude Include="X86TestSupport\xtensa\core-macros.h" />
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<ClCompile Include="Grbl_Esp32\src\Configuration\AfterParse.cpp" /> <ClCompile Include="Grbl_Esp32\src\Configuration\AfterParse.cpp" />
@@ -224,7 +234,9 @@
<ClCompile Include="Grbl_Esp32\src\Machine\Axis.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\Axis.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\Endstops.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\Endstops.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\Gang.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\Gang.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\Homing.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\I2SOBus.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\I2SOBus.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\LimitPin.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\MachineConfig.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\MachineConfig.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\SPIBus.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\SPIBus.cpp" />
<ClCompile Include="Grbl_Esp32\src\Machine\UserOutputs.cpp" /> <ClCompile Include="Grbl_Esp32\src\Machine\UserOutputs.cpp" />
@@ -244,7 +256,7 @@
<ClCompile Include="Grbl_Esp32\src\Pins\ErrorPinDetail.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\ErrorPinDetail.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\GPIOPinDetail.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\GPIOPinDetail.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\I2SOPinDetail.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\I2SOPinDetail.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\Ledc.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\LedcPin.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\PinAttributes.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\PinAttributes.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\PinCapabilities.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\PinCapabilities.cpp" />
<ClCompile Include="Grbl_Esp32\src\Pins\PinDetail.cpp" /> <ClCompile Include="Grbl_Esp32\src\Pins\PinDetail.cpp" />
@@ -308,13 +320,20 @@
<ClCompile Include="X86TestSupport\Arduino.cpp" /> <ClCompile Include="X86TestSupport\Arduino.cpp" />
<ClCompile Include="X86TestSupport\driver\dac.cpp" /> <ClCompile Include="X86TestSupport\driver\dac.cpp" />
<ClCompile Include="X86TestSupport\driver\ledc.cpp" /> <ClCompile Include="X86TestSupport\driver\ledc.cpp" />
<ClCompile Include="X86TestSupport\driver\rmt.cpp" />
<ClCompile Include="X86TestSupport\driver\uartdriver.cpp" /> <ClCompile Include="X86TestSupport\driver\uartdriver.cpp" />
<ClCompile Include="X86TestSupport\esp32-hal-timer.cpp" />
<ClCompile Include="X86TestSupport\ExceptionHelper.cpp" /> <ClCompile Include="X86TestSupport\ExceptionHelper.cpp" />
<ClCompile Include="X86TestSupport\freertos\Queue.cpp" /> <ClCompile Include="X86TestSupport\freertos\Queue.cpp" />
<ClCompile Include="X86TestSupport\freertos\Task.cpp" /> <ClCompile Include="X86TestSupport\freertos\Task.cpp" />
<ClCompile Include="X86TestSupport\FS.cpp" /> <ClCompile Include="X86TestSupport\FS.cpp" />
<ClCompile Include="X86TestSupport\I2SO.cpp" />
<ClCompile Include="X86TestSupport\nvs.cpp" /> <ClCompile Include="X86TestSupport\nvs.cpp" />
<ClCompile Include="X86TestSupport\Print.cpp" /> <ClCompile Include="X86TestSupport\Print.cpp" />
<ClCompile Include="X86TestSupport\SDFS.cpp" />
<ClCompile Include="X86TestSupport\soc\ledc_struct.cpp" />
<ClCompile Include="X86TestSupport\SPI.cpp" />
<ClCompile Include="X86TestSupport\SPIFFS.cpp" />
<ClCompile Include="X86TestSupport\Stream.cpp" /> <ClCompile Include="X86TestSupport\Stream.cpp" />
<ClCompile Include="X86TestSupport\WString.cpp" /> <ClCompile Include="X86TestSupport\WString.cpp" />
</ItemGroup> </ItemGroup>

View File

@@ -46,6 +46,12 @@
<Filter Include="X86TestSupport\soc"> <Filter Include="X86TestSupport\soc">
<UniqueIdentifier>{2fe0b2ec-2f5f-44c9-8e5d-33a53d96d80c}</UniqueIdentifier> <UniqueIdentifier>{2fe0b2ec-2f5f-44c9-8e5d-33a53d96d80c}</UniqueIdentifier>
</Filter> </Filter>
<Filter Include="X86TestSupport\xtensa">
<UniqueIdentifier>{65268649-7855-443e-bf8e-984388ea6c17}</UniqueIdentifier>
</Filter>
<Filter Include="X86TestSupport\TMC">
<UniqueIdentifier>{52fb1ffd-68a9-4edc-aae1-ca2cdf3e7da9}</UniqueIdentifier>
</Filter>
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<ClInclude Include="Grbl_Esp32\src\Machine\SPIBus.h"> <ClInclude Include="Grbl_Esp32\src\Machine\SPIBus.h">
@@ -270,9 +276,6 @@
<ClInclude Include="Grbl_Esp32\src\Assert.h"> <ClInclude Include="Grbl_Esp32\src\Assert.h">
<Filter>src</Filter> <Filter>src</Filter>
</ClInclude> </ClInclude>
<ClInclude Include="X86TestSupport\TMC\TMCStepper.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="Grbl_Esp32\src\Spindles\Laser.h"> <ClInclude Include="Grbl_Esp32\src\Spindles\Laser.h">
<Filter>src\Spindles</Filter> <Filter>src\Spindles</Filter>
</ClInclude> </ClInclude>
@@ -300,12 +303,6 @@
<ClInclude Include="Grbl_Esp32\src\Machine\WifiSTAConfig.h"> <ClInclude Include="Grbl_Esp32\src\Machine\WifiSTAConfig.h">
<Filter>src\Machine</Filter> <Filter>src\Machine</Filter>
</ClInclude> </ClInclude>
<ClInclude Include="X86TestSupport\TMC\TMCStepper_UTILITY.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\TMCStepper.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="Grbl_Esp32\src\Error.h"> <ClInclude Include="Grbl_Esp32\src\Error.h">
<Filter>src</Filter> <Filter>src</Filter>
</ClInclude> </ClInclude>
@@ -360,9 +357,6 @@
<ClInclude Include="Grbl_Esp32\src\Jog.h"> <ClInclude Include="Grbl_Esp32\src\Jog.h">
<Filter>src</Filter> <Filter>src</Filter>
</ClInclude> </ClInclude>
<ClInclude Include="Grbl_Esp32\src\Pins\Ledc.h">
<Filter>src\Pins</Filter>
</ClInclude>
<ClInclude Include="Grbl_Esp32\src\Spindles\RelaySpindle.h"> <ClInclude Include="Grbl_Esp32\src\Spindles\RelaySpindle.h">
<Filter>src\Spindles</Filter> <Filter>src\Spindles</Filter>
</ClInclude> </ClInclude>
@@ -510,6 +504,48 @@
<ClInclude Include="Grbl_Esp32\src\Stepping.h"> <ClInclude Include="Grbl_Esp32\src\Stepping.h">
<Filter>src</Filter> <Filter>src</Filter>
</ClInclude> </ClInclude>
<ClInclude Include="X86TestSupport\esp_attr.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\xtensa\core-macros.h">
<Filter>X86TestSupport\xtensa</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\TMC\TMCStepper.h">
<Filter>X86TestSupport\TMC</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\TMC\TMCStepper_UTILITY.h">
<Filter>X86TestSupport\TMC</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-gpio.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-timer.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-ledc.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-dac.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\Esp.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-cpu.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="Grbl_Esp32\src\Machine\LimitPin.h">
<Filter>src\Machine</Filter>
</ClInclude>
<ClInclude Include="X86TestSupport\esp32-hal-matrix.h">
<Filter>X86TestSupport</Filter>
</ClInclude>
<ClInclude Include="Grbl_Esp32\src\Pins\LedcPin.h">
<Filter>src\Pins</Filter>
</ClInclude>
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<ClCompile Include="Grbl_Esp32\src\WebUI\JSONEncoder.cpp"> <ClCompile Include="Grbl_Esp32\src\WebUI\JSONEncoder.cpp">
@@ -638,9 +674,6 @@
<ClCompile Include="Grbl_Esp32\src\WebUI\InputBuffer.cpp"> <ClCompile Include="Grbl_Esp32\src\WebUI\InputBuffer.cpp">
<Filter>src\WebUI</Filter> <Filter>src\WebUI</Filter>
</ClCompile> </ClCompile>
<ClCompile Include="Grbl_Esp32\src\Pins\Ledc.cpp">
<Filter>src\Pins</Filter>
</ClCompile>
<ClCompile Include="Grbl_Esp32\src\UserOutput.cpp"> <ClCompile Include="Grbl_Esp32\src\UserOutput.cpp">
<Filter>src</Filter> <Filter>src</Filter>
</ClCompile> </ClCompile>
@@ -860,6 +893,34 @@
<ClCompile Include="Grbl_Esp32\src\Stepping.cpp"> <ClCompile Include="Grbl_Esp32\src\Stepping.cpp">
<Filter>src</Filter> <Filter>src</Filter>
</ClCompile> </ClCompile>
<ClCompile Include="Grbl_Esp32\src\Machine\LimitPin.cpp">
<Filter>src\Machine</Filter>
</ClCompile>
<ClCompile Include="Grbl_Esp32\src\Machine\Homing.cpp">
<Filter>src\Machine</Filter>
</ClCompile>
<ClCompile Include="Grbl_Esp32\src\Pins\LedcPin.cpp">
<Filter>src\Pins</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\SDFS.cpp">
<Filter>X86TestSupport</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\SPI.cpp">
<Filter>X86TestSupport</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\SPIFFS.cpp">
<Filter>X86TestSupport</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\I2SO.cpp">
<Filter>X86TestSupport</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\soc\ledc_struct.cpp">
<Filter>X86TestSupport\soc</Filter>
</ClCompile>
<ClCompile Include="X86TestSupport\driver\rmt.cpp" />
<ClCompile Include="X86TestSupport\esp32-hal-timer.cpp">
<Filter>X86TestSupport</Filter>
</ClCompile>
</ItemGroup> </ItemGroup>
<ItemGroup> <ItemGroup>
<None Include="Grbl_Esp32\src\SimpleOutputStream.md"> <None Include="Grbl_Esp32\src\SimpleOutputStream.md">

View File

@@ -1,10 +1,15 @@
#include "Arduino.h" #include "Arduino.h"
#include "SoftwareGPIO.h" #include "SoftwareGPIO.h"
#include "Capture.h"
#include <chrono> #include <chrono>
#include <thread> #include <thread>
int64_t esp_timer_get_time() {
return Capture::instance().current();
}
void attachInterrupt(uint8_t pin, void (*callback)(void), int mode) { void attachInterrupt(uint8_t pin, void (*callback)(void), int mode) {
attachInterruptArg( attachInterruptArg(
pin, pin,

View File

@@ -10,38 +10,6 @@ class SystemRestartException {};
// From Arduino.h: // From Arduino.h:
// Interrupt Modes
#define RISING 0x01
#define FALLING 0x02
#define CHANGE 0x03
// #define ONLOW 0x04 --> Weird. Same as falling / rising?
// #define ONHIGH 0x05
// #define ONLOW_WE 0x0C --> not sure about these
// #define ONHIGH_WE 0x0D
// From esp32-hal-gpio.h:
#define LOW 0x0
#define HIGH 0x1
// GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
// #define OPEN_DRAIN 0x10
// #define OUTPUT_OPEN_DRAIN 0x12
void attachInterrupt(uint8_t pin, void (*)(void), int mode);
void attachInterruptArg(uint8_t pin, void (*)(void*), void* arg, int mode);
void detachInterrupt(uint8_t pin);
extern "C" int __digitalRead(uint8_t pin);
extern "C" void __pinMode(uint8_t pin, uint8_t mode);
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);
void delay(int ms); void delay(int ms);
// Get time in microseconds since boot. // Get time in microseconds since boot.
@@ -52,119 +20,8 @@ int64_t esp_timer_get_time();
do { \ do { \
} while (0); } while (0);
typedef enum {
GPIO_NUM_0 = 0, /*!< GPIO0, input and output */
GPIO_NUM_1 = 1, /*!< GPIO1, input and output */
GPIO_NUM_2 = 2, /*!< GPIO2, input and output
@note There are more enumerations like that
up to GPIO39, excluding GPIO20, GPIO24 and GPIO28..31.
They are not shown here to reduce redundant information.
@note GPIO34..39 are input mode only. */
/** @cond */
GPIO_NUM_3 = 3, /*!< GPIO3, input and output */
GPIO_NUM_4 = 4, /*!< GPIO4, input and output */
GPIO_NUM_5 = 5, /*!< GPIO5, input and output */
GPIO_NUM_6 = 6, /*!< GPIO6, input and output */
GPIO_NUM_7 = 7, /*!< GPIO7, input and output */
GPIO_NUM_8 = 8, /*!< GPIO8, input and output */
GPIO_NUM_9 = 9, /*!< GPIO9, input and output */
GPIO_NUM_10 = 10, /*!< GPIO10, input and output */
GPIO_NUM_11 = 11, /*!< GPIO11, input and output */
GPIO_NUM_12 = 12, /*!< GPIO12, input and output */
GPIO_NUM_13 = 13, /*!< GPIO13, input and output */
GPIO_NUM_14 = 14, /*!< GPIO14, input and output */
GPIO_NUM_15 = 15, /*!< GPIO15, input and output */
GPIO_NUM_16 = 16, /*!< GPIO16, input and output */
GPIO_NUM_17 = 17, /*!< GPIO17, input and output */
GPIO_NUM_18 = 18, /*!< GPIO18, input and output */
GPIO_NUM_19 = 19, /*!< GPIO19, input and output */
GPIO_NUM_21 = 21, /*!< GPIO21, input and output */
GPIO_NUM_22 = 22, /*!< GPIO22, input and output */
GPIO_NUM_23 = 23, /*!< GPIO23, input and output */
GPIO_NUM_25 = 25, /*!< GPIO25, input and output */
GPIO_NUM_26 = 26, /*!< GPIO26, input and output */
GPIO_NUM_27 = 27, /*!< GPIO27, input and output */
GPIO_NUM_32 = 32, /*!< GPIO32, input and output */
GPIO_NUM_33 = 33, /*!< GPIO33, input and output */
GPIO_NUM_34 = 34, /*!< GPIO34, input mode only */
GPIO_NUM_35 = 35, /*!< GPIO35, input mode only */
GPIO_NUM_36 = 36, /*!< GPIO36, input mode only */
GPIO_NUM_37 = 37, /*!< GPIO37, input mode only */
GPIO_NUM_38 = 38, /*!< GPIO38, input mode only */
GPIO_NUM_39 = 39, /*!< GPIO39, input mode only */
GPIO_NUM_MAX = 40,
/** @endcond */
} gpio_num_t;
#define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) #define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt)))
// PWM:
uint32_t getApbFrequency(); // In Hz
double ledcSetup(uint8_t channel, double freq, uint8_t resolution_bits);
void ledcWrite(uint8_t channel, uint32_t duty);
void ledcAttachPin(uint8_t pin, uint8_t channel);
void ledcDetachPin(uint8_t pin);
// Timer:
struct hw_timer_s;
typedef struct hw_timer_s hw_timer_t;
void timerAlarmEnable(hw_timer_t* timer);
void timerAlarmDisable(hw_timer_t* timer);
void timerWrite(hw_timer_t* timer, uint64_t val);
void timerAlarmWrite(hw_timer_t* timer, uint64_t interruptAt, bool autoreload);
hw_timer_t* timerBegin(uint8_t timer, uint16_t divider, bool countUp);
void timerEnd(hw_timer_t* timer);
void timerAttachInterrupt(hw_timer_t* timer, void (*fn)(void), bool edge);
void timerDetachInterrupt(hw_timer_t* timer);
// Figure this out:
extern "C" {
esp_err_t esp_task_wdt_reset(void);
}
unsigned long micros();
unsigned long millis();
void delay(uint32_t);
void delayMicroseconds(uint32_t us);
// ESP... // ESP...
typedef enum { #include "Esp.h"
ESP_RST_UNKNOWN, //!< Reset reason can not be determined
ESP_RST_POWERON, //!< Reset due to power-on event
ESP_RST_EXT, //!< Reset by external pin (not applicable for ESP32)
ESP_RST_SW, //!< Software reset via esp_restart
ESP_RST_PANIC, //!< Software reset due to exception/panic
ESP_RST_INT_WDT, //!< Reset (software or hardware) due to interrupt watchdog
ESP_RST_TASK_WDT, //!< Reset due to task watchdog
ESP_RST_WDT, //!< Reset due to other watchdogs
ESP_RST_DEEPSLEEP, //!< Reset after exiting deep sleep mode
ESP_RST_BROWNOUT, //!< Brownout reset (software or hardware)
ESP_RST_SDIO, //!< Reset over SDIO
} esp_reset_reason_t;
esp_reset_reason_t esp_reset_reason(void);
struct EspClass {
uint64_t getEfuseMac();
uint32_t getCpuFreqMHz();
const char* getSdkVersion();
uint32_t getFreeHeap();
uint32_t getFlashChipSize();
void restart();
};
extern EspClass ESP;
inline long map(long x, long in_min, long in_max, long out_min, long out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
int temperatureRead(void);

View File

@@ -97,7 +97,7 @@ public:
} }
void set(const std::string& id, const std::vector<uint32_t>& value) { void set(const std::string& id, const std::vector<uint32_t>& value) {
auto it = data_.find(id); auto it = data_.find(id);
if (it == data_.end()) { if (it == data_.end()) {
data_.insert(std::make_pair(id, value)); data_.insert(std::make_pair(id, value));
} else { } else {

36
X86TestSupport/Esp.h Normal file
View File

@@ -0,0 +1,36 @@
#pragma once
#include <cstdint>
typedef enum {
ESP_RST_UNKNOWN, //!< Reset reason can not be determined
ESP_RST_POWERON, //!< Reset due to power-on event
ESP_RST_EXT, //!< Reset by external pin (not applicable for ESP32)
ESP_RST_SW, //!< Software reset via esp_restart
ESP_RST_PANIC, //!< Software reset due to exception/panic
ESP_RST_INT_WDT, //!< Reset (software or hardware) due to interrupt watchdog
ESP_RST_TASK_WDT, //!< Reset due to task watchdog
ESP_RST_WDT, //!< Reset due to other watchdogs
ESP_RST_DEEPSLEEP, //!< Reset after exiting deep sleep mode
ESP_RST_BROWNOUT, //!< Brownout reset (software or hardware)
ESP_RST_SDIO, //!< Reset over SDIO
} esp_reset_reason_t;
esp_reset_reason_t esp_reset_reason(void);
struct EspClass {
uint64_t getEfuseMac();
uint32_t getCpuFreqMHz();
const char* getSdkVersion();
uint32_t getFreeHeap();
uint32_t getFlashChipSize();
void restart();
};
extern EspClass ESP;
inline long map(long x, long in_min, long in_max, long out_min, long out_max) {
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
int temperatureRead(void);

35
X86TestSupport/I2SO.cpp Normal file
View File

@@ -0,0 +1,35 @@
#include <src/I2SOut.h>
// STUB implementation. Won't do you any good.
int i2s_out_init() {
return 0;
}
void i2s_out_push() {}
unsigned int i2s_out_push_sample(unsigned int x) {
return x;
}
int i2s_out_set_passthrough() {
return 0;
}
int i2s_out_set_stepping() {
return 0;
}
void i2s_out_delay() {}
int i2s_out_set_pulse_period(unsigned int x) {
return 0;
}
int i2s_out_reset() {
return 0;
}
i2s_out_pulser_status_t i2s_out_get_pulser_status() {
return i2s_out_pulser_status_t::PASSTHROUGH;
}

19
X86TestSupport/SDFS.cpp Normal file
View File

@@ -0,0 +1,19 @@
#include "SD.h"
namespace fs {
SDFS::SDFS(FSImplPtr impl) : fs::FS(impl) {}
bool SDFS::begin(uint8_t ssPin, SPIClass& spi, uint32_t frequency, const char* mountpoint, uint8_t max_files, bool format_if_empty) {
return true;
}
void SDFS::end() {}
uint64_t SDFS::cardSize() { return 0; }
uint64_t SDFS::totalBytes() { return 0; }
uint64_t SDFS::usedBytes() { return 0; }
bool SDFS::readRAW(uint8_t* buffer, uint32_t sector) { return false; }
bool SDFS::writeRAW(uint8_t* buffer, uint32_t sector) { return false; }
FSImplPtr inst;
}
fs::SDFS SD(fs::inst);

3
X86TestSupport/SPI.cpp Normal file
View File

@@ -0,0 +1,3 @@
#include "SPI.h"
SPIClass SPI;

19
X86TestSupport/SPIFFS.cpp Normal file
View File

@@ -0,0 +1,19 @@
#include "SPIFFS.h"
namespace fs {
SPIFFSFS::SPIFFSFS() : fs::FS(nullptr), partitionLabel_("spiffs") {}
SPIFFSFS::~SPIFFSFS() {}
bool SPIFFSFS::begin(bool formatOnFail /* = false*/,
const char* basePath /*= "/spiffs"*/,
uint8_t maxOpenFiles /*= 10*/,
const char* partitionLabel /*= NULL*/) {
return true;
}
bool SPIFFSFS::format() { return true; }
size_t SPIFFSFS::totalBytes() { return 1024 * 1024; /* 1 MB */ }
size_t SPIFFSFS::usedBytes() { return 0; }
void SPIFFSFS::end() {}
}
fs::SPIFFSFS SPIFFS;

View File

@@ -12,8 +12,7 @@
// See the License for the specific language governing permissions and // See the License for the specific language governing permissions and
// limitations under the License. // limitations under the License.
#ifndef _SPIFFS_H_ #pragma once
#define _SPIFFS_H_
#include "FS.h" #include "FS.h"
@@ -36,5 +35,3 @@ namespace fs {
} }
extern fs::SPIFFSFS SPIFFS; extern fs::SPIFFSFS SPIFFS;
#endif

View File

@@ -3,6 +3,7 @@
#include "Arduino.h" #include "Arduino.h"
#include <src/Assert.h> #include <src/Assert.h>
#include <random> #include <random>
#include "esp32-hal-gpio.h"
struct SoftwarePin { struct SoftwarePin {
SoftwarePin() : callback(), argument(nullptr), mode(0), driverValue(false), padValue(false), pinMode(0) {} SoftwarePin() : callback(), argument(nullptr), mode(0), driverValue(false), padValue(false), pinMode(0) {}

View File

@@ -22,11 +22,11 @@
#include "Arduino.h" #include "Arduino.h"
#include "Stream.h" #include "Stream.h"
#include "esp32-hal.h"
#define PARSE_TIMEOUT 1000 // default number of milli-seconds to wait #define PARSE_TIMEOUT 1000 // default number of milli-seconds to wait
#define NO_SKIP_CHAR 1 // a magic char not found in a valid ASCII numeric field #define NO_SKIP_CHAR 1 // a magic char not found in a valid ASCII numeric field
/*
// private method to read stream with timeout // private method to read stream with timeout
int Stream::timedRead() { int Stream::timedRead() {
int c; int c;
@@ -52,7 +52,6 @@ int Stream::timedPeek() {
} while ((millis() - _startMillis) < _timeout); } while ((millis() - _startMillis) < _timeout);
return -1; // -1 indicates timeout return -1; // -1 indicates timeout
} }
*/
// returns peek of the next digit in the stream or -1 if timeout // returns peek of the next digit in the stream or -1 if timeout
// discards non-numeric characters // discards non-numeric characters
@@ -86,20 +85,30 @@ unsigned long Stream::getTimeout(void) {
// find returns true if the target string is found // find returns true if the target string is found
bool Stream::find(const char* target) { bool Stream::find(const char* target) {
return findUntil(target, strlen(target), NULL, 0); return find(target, strlen(target));
} }
// reads data from the stream until the target string of given length is found // reads data from the stream until the target string of given length is found
// returns true if target string is found, false if timed out // returns true if target string is found, false if timed out
bool Stream::find(const char* target, size_t length) { bool Stream::find(const char* target, size_t targetLen) {
return findUntil(target, length, NULL, 0); int targetIdx = 0;
while (targetIdx < targetLen) {
auto current = read();
if (current == target[targetIdx]) {
++targetIdx;
} else {
targetIdx = 0;
}
}
return targetIdx == targetLen;
} }
/*
// as find but search ends if the terminator string is found // as find but search ends if the terminator string is found
bool Stream::findUntil(const char* target, const char* terminator) { bool Stream::findUntil(const char* target, const char* terminator) {
return findUntil(target, strlen(target), terminator, strlen(terminator)); return findUntil(target, strlen(target), terminator, strlen(terminator));
} }
/*
// reads data from the stream until the target string of the given length is found // reads data from the stream until the target string of the given length is found
// search terminated if the terminator string is found // search terminated if the terminator string is found
// returns true if target string is found, false if terminated or timed out // returns true if target string is found, false if terminated or timed out

View File

@@ -66,6 +66,7 @@ public:
bool find(char target) { return find(&target, 1); } bool find(char target) { return find(&target, 1); }
/*
bool findUntil(const char* target, const char* terminator); // as find but search ends if the terminator string is found bool findUntil(const char* target, const char* terminator); // as find but search ends if the terminator string is found
bool findUntil(const uint8_t* target, const char* terminator) { return findUntil((char*)target, terminator); } bool findUntil(const uint8_t* target, const char* terminator) { return findUntil((char*)target, terminator); }
@@ -76,6 +77,7 @@ public:
bool findUntil(const uint8_t* target, size_t targetLen, const char* terminate, size_t termLen) { bool findUntil(const uint8_t* target, size_t targetLen, const char* terminate, size_t termLen) {
return findUntil((char*)target, targetLen, terminate, termLen); return findUntil((char*)target, targetLen, terminate, termLen);
} }
*/
long parseInt(); // returns the first valid (long) integer value from the current position. long parseInt(); // returns the first valid (long) integer value from the current position.
// initial characters that are not digits (or the minus sign) are skipped // initial characters that are not digits (or the minus sign) are skipped

View File

@@ -1 +0,0 @@
#pragma once

View File

@@ -2,5 +2,12 @@
#include <cstdint> #include <cstdint>
// PWM:
uint32_t getApbFrequency(); // In Hz
double ledcSetup(uint8_t channel, double freq, uint8_t resolution_bits);
void ledcWrite(uint8_t channel, uint32_t duty);
void ledcAttachPin(uint8_t pin, uint8_t channel);
void ledcDetachPin(uint8_t pin);
void pinMatrixOutAttach(uint8_t pin, uint8_t function, bool invertOut, bool invertEnable); void pinMatrixOutAttach(uint8_t pin, uint8_t function, bool invertOut, bool invertEnable);
void pinMatrixOutDetach(uint8_t pin, bool invertOut, bool invertEnable); void pinMatrixOutDetach(uint8_t pin, bool invertOut, bool invertEnable);

View File

@@ -0,0 +1,16 @@
#include "rmt.h"
rmt_dev_t RMT;
esp_err_t rmt_set_source_clk(rmt_channel_t channel, rmt_source_clk_t base_clk) {
return ESP_OK;
}
esp_err_t rmt_config(const rmt_config_t* rmt_param) {
// TODO: figure out the stuff that matter, and push them.
return ESP_OK;
}
esp_err_t rmt_fill_tx_items(rmt_channel_t channel, const rmt_item32_t* item, uint16_t item_num, uint16_t mem_offset) {
// TODO: figure out the stuff that matter, and push them.
return ESP_OK;
}

View File

@@ -14,6 +14,10 @@
#pragma once #pragma once
#include <cstdint>
#include "../esp_err.h"
typedef struct rmt_item32_s { typedef struct rmt_item32_s {
union { union {
struct { struct {
@@ -350,4 +354,5 @@ typedef volatile struct rmt_dev_s {
uint32_t reserved_f8; uint32_t reserved_f8;
uint32_t date; /*This is the version register.*/ uint32_t date; /*This is the version register.*/
} rmt_dev_t; } rmt_dev_t;
extern rmt_dev_t RMT; extern rmt_dev_t RMT;

View File

@@ -0,0 +1,3 @@
#pragma once
#include "driver/ledc.h"

View File

@@ -0,0 +1,3 @@
#pragma once
#include "driver/dac.h"

View File

@@ -0,0 +1,82 @@
#pragma once
#include <cstdint>
// Interrupt Modes
#define RISING 0x01
#define FALLING 0x02
#define CHANGE 0x03
// #define ONLOW 0x04 --> Weird. Same as falling / rising?
// #define ONHIGH 0x05
// #define ONLOW_WE 0x0C --> not sure about these
// #define ONHIGH_WE 0x0D
typedef enum {
GPIO_NUM_0 = 0, /*!< GPIO0, input and output */
GPIO_NUM_1 = 1, /*!< GPIO1, input and output */
GPIO_NUM_2 = 2, /*!< GPIO2, input and output
@note There are more enumerations like that
up to GPIO39, excluding GPIO20, GPIO24 and GPIO28..31.
They are not shown here to reduce redundant information.
@note GPIO34..39 are input mode only. */
/** @cond */
GPIO_NUM_3 = 3, /*!< GPIO3, input and output */
GPIO_NUM_4 = 4, /*!< GPIO4, input and output */
GPIO_NUM_5 = 5, /*!< GPIO5, input and output */
GPIO_NUM_6 = 6, /*!< GPIO6, input and output */
GPIO_NUM_7 = 7, /*!< GPIO7, input and output */
GPIO_NUM_8 = 8, /*!< GPIO8, input and output */
GPIO_NUM_9 = 9, /*!< GPIO9, input and output */
GPIO_NUM_10 = 10, /*!< GPIO10, input and output */
GPIO_NUM_11 = 11, /*!< GPIO11, input and output */
GPIO_NUM_12 = 12, /*!< GPIO12, input and output */
GPIO_NUM_13 = 13, /*!< GPIO13, input and output */
GPIO_NUM_14 = 14, /*!< GPIO14, input and output */
GPIO_NUM_15 = 15, /*!< GPIO15, input and output */
GPIO_NUM_16 = 16, /*!< GPIO16, input and output */
GPIO_NUM_17 = 17, /*!< GPIO17, input and output */
GPIO_NUM_18 = 18, /*!< GPIO18, input and output */
GPIO_NUM_19 = 19, /*!< GPIO19, input and output */
GPIO_NUM_21 = 21, /*!< GPIO21, input and output */
GPIO_NUM_22 = 22, /*!< GPIO22, input and output */
GPIO_NUM_23 = 23, /*!< GPIO23, input and output */
GPIO_NUM_25 = 25, /*!< GPIO25, input and output */
GPIO_NUM_26 = 26, /*!< GPIO26, input and output */
GPIO_NUM_27 = 27, /*!< GPIO27, input and output */
GPIO_NUM_32 = 32, /*!< GPIO32, input and output */
GPIO_NUM_33 = 33, /*!< GPIO33, input and output */
GPIO_NUM_34 = 34, /*!< GPIO34, input mode only */
GPIO_NUM_35 = 35, /*!< GPIO35, input mode only */
GPIO_NUM_36 = 36, /*!< GPIO36, input mode only */
GPIO_NUM_37 = 37, /*!< GPIO37, input mode only */
GPIO_NUM_38 = 38, /*!< GPIO38, input mode only */
GPIO_NUM_39 = 39, /*!< GPIO39, input mode only */
GPIO_NUM_MAX = 40,
/** @endcond */
} gpio_num_t;
// From esp32-hal-gpio.h:
#define LOW 0x0
#define HIGH 0x1
// GPIO FUNCTIONS
#define INPUT 0x01
#define OUTPUT 0x02
#define PULLUP 0x04
#define INPUT_PULLUP 0x05
#define PULLDOWN 0x08
#define INPUT_PULLDOWN 0x09
// #define OPEN_DRAIN 0x10
// #define OUTPUT_OPEN_DRAIN 0x12
void attachInterrupt(uint8_t pin, void (*)(void), int mode);
void attachInterruptArg(uint8_t pin, void (*)(void*), void* arg, int mode);
void detachInterrupt(uint8_t pin);
extern "C" int __digitalRead(uint8_t pin);
extern "C" void __pinMode(uint8_t pin, uint8_t mode);
extern "C" void __digitalWrite(uint8_t pin, uint8_t val);

View File

@@ -0,0 +1,3 @@
#pragma once
#include "driver/ledc.h"

View File

@@ -0,0 +1,3 @@
#pragma once
#include "driver/ledc.h"

View File

@@ -0,0 +1,31 @@
#include "esp32-hal-timer.h"
uint32_t g_ticks_per_us_pro = 240 * 1000 * 1000; // For CPU 0 - typically 240 MHz
uint32_t g_ticks_per_us_app = 240 * 1000 * 1000; // For CPU 1 - typically 240 MHz
struct hw_timer_s {};
// TODO: These are just stubs.
void timerAlarmEnable(hw_timer_t* timer) {}
void timerAlarmDisable(hw_timer_t* timer) {}
void timerWrite(hw_timer_t* timer, uint64_t val) {}
void timerAlarmWrite(hw_timer_t* timer, uint64_t interruptAt, bool autoreload) {}
hw_timer_t* timerBegin(uint8_t timer, uint16_t divider, bool countUp) {
return new hw_timer_t();
}
void timerEnd(hw_timer_t* timer) {
delete timer;
}
void timerAttachInterrupt(hw_timer_t* timer, void (*fn)(void), bool edge) {}
void timerDetachInterrupt(hw_timer_t* timer) {}
// Figure this out:
extern "C" {
esp_err_t esp_task_wdt_reset(void) {
return ESP_OK;
}
}

View File

@@ -0,0 +1,33 @@
#pragma once
#include <cstdint>
#include "esp_err.h"
extern uint32_t g_ticks_per_us_pro; // For CPU 0 - typically 240 MHz
extern uint32_t g_ticks_per_us_app; // For CPU 1 - typically 240 MHz
// Timer:
struct hw_timer_s;
typedef struct hw_timer_s hw_timer_t;
void timerAlarmEnable(hw_timer_t* timer);
void timerAlarmDisable(hw_timer_t* timer);
void timerWrite(hw_timer_t* timer, uint64_t val);
void timerAlarmWrite(hw_timer_t* timer, uint64_t interruptAt, bool autoreload);
hw_timer_t* timerBegin(uint8_t timer, uint16_t divider, bool countUp);
void timerEnd(hw_timer_t* timer);
void timerAttachInterrupt(hw_timer_t* timer, void (*fn)(void), bool edge);
void timerDetachInterrupt(hw_timer_t* timer);
// Figure this out:
extern "C" {
esp_err_t esp_task_wdt_reset(void);
}
unsigned long micros();
unsigned long millis();
void delay(uint32_t);
void delayMicroseconds(uint32_t us);

View File

@@ -0,0 +1,3 @@
#pragma once
#include "esp32-hal-timer.h"

View File

@@ -0,0 +1,3 @@
#pragma once
#include "Arduino.h"

View File

@@ -4,10 +4,28 @@
#include "Queue.h" #include "Queue.h"
#include "FreeRTOSTypes.h" #include "FreeRTOSTypes.h"
#include <mutex> #include <mutex>
#include <atomic>
/* "mux" data structure (spinlock) */ /* "mux" data structure (spinlock) */
void vTaskExitCritical(portMUX_TYPE* mux); struct portMUX_TYPE {
void vTaskEnterCritical(portMUX_TYPE* mux); std::atomic<bool> lock_ = { false };
int32_t xPortGetFreeHeapSize(); void lock() {
while (lock_.exchange(true, std::memory_order_acquire))
;
}
void unlock() { lock_.store(false, std::memory_order_release); }
};
inline void vTaskExitCritical(portMUX_TYPE* mux) {
mux->lock();
}
inline void vTaskEnterCritical(portMUX_TYPE* mux) {
mux->unlock();
}
inline int32_t xPortGetFreeHeapSize() {
return 1024 * 1024 * 4;
}

View File

@@ -2,8 +2,6 @@
#include <mutex> #include <mutex>
using portMUX_TYPE = std::mutex;
#define portMAX_DELAY (TickType_t)0xffffffffUL #define portMAX_DELAY (TickType_t)0xffffffffUL
using portBASE_TYPE = int; using portBASE_TYPE = int;

View File

@@ -0,0 +1,3 @@
#include "ledc_struct.h"
ledc_dev_t LEDC;

View File

@@ -1,5 +1,7 @@
#pragma once #pragma once
#include <cstdint>
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD // Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
// //
// Licensed under the Apache License, Version 2.0 (the "License"); // Licensed under the Apache License, Version 2.0 (the "License");

View File

@@ -0,0 +1,7 @@
#pragma once
#include "../esp32-hal-timer.h"
inline int32_t IRAM_ATTR XTHAL_GET_CCOUNT() {
return int32_t(millis());
}