From 654c4082a3ec6cf99691939bc6702ce9438944c0 Mon Sep 17 00:00:00 2001 From: Stefan de Bruijn Date: Tue, 29 Jun 2021 16:12:53 +0200 Subject: [PATCH] Fixed a bunch of minor bugs. Added more X86 test support code. --- Grbl_Esp32/src/Configuration/ParserHandler.h | 1 + Grbl_Esp32/src/Grbl.cpp | 15 +- Grbl_Esp32/src/I2SOut.cpp | 2 +- Grbl_Esp32/src/Limits.cpp | 7 +- Grbl_Esp32/src/Limits.h | 2 +- Grbl_Esp32/src/Machine/Axis.cpp | 2 + Grbl_Esp32/src/Machine/Homing.h | 12 +- Grbl_Esp32/src/Machine/MachineConfig.h | 4 +- Grbl_Esp32/src/MotionControl.cpp | 11 +- Grbl_Esp32/src/Motors/Dynamixel2.cpp | 2 + Grbl_Esp32/src/Motors/Motor.cpp | 4 +- Grbl_Esp32/src/Pins/DebugPinDetail.cpp | 15 +- Grbl_Esp32/src/Platform.h | 13 + Grbl_Esp32/src/Report.cpp | 1 + Grbl_Esp32/src/Settings.cpp | 5 +- Grbl_Esp32/src/Spindles/HuanyangSpindle.cpp | 2 + Grbl_Esp32/src/Spindles/Spindle.cpp | 2 +- Grbl_Esp32/src/Spindles/YL620Spindle.cpp | 6 +- Grbl_Esp32/src/Uart.h | 1 + Grbl_Esp32/src/WebUI/Commands.cpp | 3 + Grbl_Esp32/src/WebUI/WebSettings.cpp | 20 +- Grbl_Esp32/src/WebUI/WifiConfig.h | 2 + .../test/Pins/{Error.cpp => ErrorPinTest.cpp} | 0 UnitTests.vcxproj | 217 ++- UnitTests.vcxproj.filters | 816 +++++++++-- X86TestSupport/Arduino.h | 127 ++ X86TestSupport/FS.cpp | 244 ++++ X86TestSupport/FS.h | 107 ++ X86TestSupport/FSImpl.h | 66 + X86TestSupport/Print.cpp | 331 +++++ X86TestSupport/Print.h | 93 ++ X86TestSupport/Printable.h | 36 + X86TestSupport/SD.h | 51 + X86TestSupport/SPI.h | 9 + X86TestSupport/SPIFFS.h | 40 + X86TestSupport/Stream.cpp | 323 +++++ X86TestSupport/Stream.h | 108 ++ X86TestSupport/TMC/TMCStepper.h | 1251 +++++++++++++++++ X86TestSupport/TMC/TMCStepper_UTILITY.h | 33 + X86TestSupport/TMCStepper.h | 1 + X86TestSupport/WString.h | 27 +- X86TestSupport/driver/dac.h | 5 + X86TestSupport/driver/ledc.h | 6 + X86TestSupport/driver/rmt.h | 353 +++++ X86TestSupport/driver/uart.h | 37 + X86TestSupport/esp_err.h | 154 ++ X86TestSupport/esp_system.h | 1 + X86TestSupport/freertos/FreeRTOS.h | 32 + X86TestSupport/freertos/Queue.h | 39 + X86TestSupport/freertos/task.h | 59 + X86TestSupport/nvs.h | 163 +++ X86TestSupport/soc/dport_reg.h | 1 + X86TestSupport/soc/gpio_sig_map.h | 1 + X86TestSupport/soc/io_mux_reg.h | 1 + X86TestSupport/soc/ledc_struct.h | 245 ++++ X86TestSupport/soc/rtc.h | 1 + X86TestSupport/soc/uart_reg.h | 1 + 57 files changed, 4978 insertions(+), 133 deletions(-) create mode 100644 Grbl_Esp32/src/Platform.h rename Grbl_Esp32/test/Pins/{Error.cpp => ErrorPinTest.cpp} (100%) create mode 100644 X86TestSupport/FS.cpp create mode 100644 X86TestSupport/FS.h create mode 100644 X86TestSupport/FSImpl.h create mode 100644 X86TestSupport/Print.cpp create mode 100644 X86TestSupport/Print.h create mode 100644 X86TestSupport/Printable.h create mode 100644 X86TestSupport/SD.h create mode 100644 X86TestSupport/SPI.h create mode 100644 X86TestSupport/SPIFFS.h create mode 100644 X86TestSupport/Stream.cpp create mode 100644 X86TestSupport/Stream.h create mode 100644 X86TestSupport/TMC/TMCStepper.h create mode 100644 X86TestSupport/TMC/TMCStepper_UTILITY.h create mode 100644 X86TestSupport/TMCStepper.h create mode 100644 X86TestSupport/driver/dac.h create mode 100644 X86TestSupport/driver/ledc.h create mode 100644 X86TestSupport/driver/rmt.h create mode 100644 X86TestSupport/esp_err.h create mode 100644 X86TestSupport/esp_system.h create mode 100644 X86TestSupport/freertos/FreeRTOS.h create mode 100644 X86TestSupport/freertos/Queue.h create mode 100644 X86TestSupport/freertos/task.h create mode 100644 X86TestSupport/nvs.h create mode 100644 X86TestSupport/soc/dport_reg.h create mode 100644 X86TestSupport/soc/gpio_sig_map.h create mode 100644 X86TestSupport/soc/io_mux_reg.h create mode 100644 X86TestSupport/soc/ledc_struct.h create mode 100644 X86TestSupport/soc/rtc.h create mode 100644 X86TestSupport/soc/uart_reg.h diff --git a/Grbl_Esp32/src/Configuration/ParserHandler.h b/Grbl_Esp32/src/Configuration/ParserHandler.h index c2493b32..42ad9193 100644 --- a/Grbl_Esp32/src/Configuration/ParserHandler.h +++ b/Grbl_Esp32/src/Configuration/ParserHandler.h @@ -21,6 +21,7 @@ #include "HandlerBase.h" #include "Parser.h" #include "Configurable.h" +#include "../System.h" #include "../Logging.h" diff --git a/Grbl_Esp32/src/Grbl.cpp b/Grbl_Esp32/src/Grbl.cpp index d127e79b..2b3a8ecf 100644 --- a/Grbl_Esp32/src/Grbl.cpp +++ b/Grbl_Esp32/src/Grbl.cpp @@ -32,11 +32,14 @@ #include "System.h" #include "Uart.h" #include "MotionControl.h" +#include "Platform.h" #include "WebUI/WifiConfig.h" #include "WebUI/InputBuffer.h" -#include +#ifdef ENABLE_WIFI +# include +#endif #include #include // sleep @@ -46,12 +49,14 @@ void grbl_init() { try { uartInit(); // Setup serial port +#ifdef ENABLE_WIFI debug_serial("Initializing WiFi..."); WiFi.persistent(false); WiFi.disconnect(true); WiFi.enableSTA(false); WiFi.enableAP(false); WiFi.mode(WIFI_OFF); +#endif display_init(); info_serial("Grbl_ESP32 Ver %s Date %s", GRBL_VERSION, GRBL_VERSION_BUILD); // print grbl_esp32 verion info @@ -204,13 +209,13 @@ void run_once() { // This is inside a loop in Grbl_Esp32.ino } -void __attribute__((weak)) machine_init() {} +void WEAK_LINK machine_init() {} -void __attribute__((weak)) display_init() {} +void WEAK_LINK display_init() {} -void __attribute__((weak)) user_m30() {} +void WEAK_LINK user_m30() {} -void __attribute__((weak)) user_tool_change(uint8_t new_tool) { +void WEAK_LINK user_tool_change(uint8_t new_tool) { Spindles::Spindle::switchSpindle(new_tool, config->_spindles, spindle); } diff --git a/Grbl_Esp32/src/I2SOut.cpp b/Grbl_Esp32/src/I2SOut.cpp index 6853803a..63a944d2 100644 --- a/Grbl_Esp32/src/I2SOut.cpp +++ b/Grbl_Esp32/src/I2SOut.cpp @@ -50,7 +50,7 @@ #include "SettingsDefinitions.h" #include "Machine/MachineConfig.h" -#include +#include #include #include #include diff --git a/Grbl_Esp32/src/Limits.cpp b/Grbl_Esp32/src/Limits.cpp index 1678ff81..8da2d2c3 100644 --- a/Grbl_Esp32/src/Limits.cpp +++ b/Grbl_Esp32/src/Limits.cpp @@ -36,6 +36,7 @@ #include "Protocol.h" // protocol_execute_realtime #include "Report.h" // info, etc #include "I2SOut.h" // I2S_OUT_DELAY_MS +#include "Platform.h" #include #include @@ -89,7 +90,7 @@ AxisMask homingAxes() { // circumvent the processes for executing motions in normal operation. // NOTE: Only the abort realtime command can interrupt this process. // TODO: Move limit pin-specific calls to a general function for portability. -void limits_go_home(uint8_t cycle_mask, uint n_locate_cycles) { +void limits_go_home(uint8_t cycle_mask, uint32_t n_locate_cycles) { if ((cycle_mask & homingAxes()) != cycle_mask) { debug_all("Homing is not configured for some requested axes"); } @@ -454,7 +455,7 @@ float limitsMinPosition(uint8_t axis) { // Checks and reports if target array exceeds machine travel limits. // Return true if exceeding limits // Set $/MaxTravel=0 to selectively remove an axis from soft limit checks -bool __attribute__((weak)) limitsCheckTravel(float* target) { +bool WEAK_LINK limitsCheckTravel(float* target) { auto axes = config->_axes; auto n_axis = axes->_numberAxis; for (int axis = 0; axis < n_axis; axis++) { @@ -477,6 +478,6 @@ bool limitsSwitchDefined(uint8_t axis, uint8_t gang_index) { } } -bool __attribute__((weak)) user_defined_homing(AxisMask cycle_mask) { +bool WEAK_LINK user_defined_homing(AxisMask cycle_mask) { return false; } diff --git a/Grbl_Esp32/src/Limits.h b/Grbl_Esp32/src/Limits.h index 10991a11..03e1bfef 100644 --- a/Grbl_Esp32/src/Limits.h +++ b/Grbl_Esp32/src/Limits.h @@ -44,7 +44,7 @@ void limits_enable(); AxisMask limits_get_state(); // Perform one homing operation -void limits_go_home(AxisMask cycle_mask, uint n_locate_cycles); +void limits_go_home(AxisMask cycle_mask, uint32_t n_locate_cycles); // Check for soft limit violations void limits_soft_check(float* target); diff --git a/Grbl_Esp32/src/Machine/Axis.cpp b/Grbl_Esp32/src/Machine/Axis.cpp index 58ce5775..d1289ef4 100644 --- a/Grbl_Esp32/src/Machine/Axis.cpp +++ b/Grbl_Esp32/src/Machine/Axis.cpp @@ -1,5 +1,7 @@ #include "Axis.h" +#include + namespace Machine { void Axis::group(Configuration::HandlerBase& handler) { handler.item("steps_per_mm", _stepsPerMm); diff --git a/Grbl_Esp32/src/Machine/Homing.h b/Grbl_Esp32/src/Machine/Homing.h index 577bb545..8f30c04c 100644 --- a/Grbl_Esp32/src/Machine/Homing.h +++ b/Grbl_Esp32/src/Machine/Homing.h @@ -28,13 +28,13 @@ namespace Machine { int _cycle = -1; bool _square = false; bool _positiveDirection = true; - float _mpos = 0; - float _feedRate = 500; - float _seekRate = 100; - float _pulloff = 1.0; // mm + float _mpos = 0.0f; + float _feedRate = 500.0f; + float _seekRate = 100.0f; + float _pulloff = 1.0f; // mm int _debounce = 10; - float _search_scaler = 1.1; - float _locate_scaler = 5.0; + float _search_scaler = 1.1f; + float _locate_scaler = 5.0f; // Configuration system helpers: void validate() const override { Assert(_cycle >= 1, "Cycle has to be defined as >= 1 for homing sequence."); } diff --git a/Grbl_Esp32/src/Machine/MachineConfig.h b/Grbl_Esp32/src/Machine/MachineConfig.h index dbeb4fe6..98066d0b 100644 --- a/Grbl_Esp32/src/Machine/MachineConfig.h +++ b/Grbl_Esp32/src/Machine/MachineConfig.h @@ -62,8 +62,8 @@ namespace Machine { int _disableDelayMicroSeconds = 0; bool _laserMode = false; - float _arcTolerance = 0.002; - float _junctionDeviation = 0.01; + float _arcTolerance = 0.002f; + float _junctionDeviation = 0.01f; uint8_t _idleTime = 255; bool _verboseErrors = false; bool _reportInches = false; diff --git a/Grbl_Esp32/src/MotionControl.cpp b/Grbl_Esp32/src/MotionControl.cpp index c9a943cd..46d2acab 100644 --- a/Grbl_Esp32/src/MotionControl.cpp +++ b/Grbl_Esp32/src/MotionControl.cpp @@ -32,6 +32,7 @@ #include "Planner.h" // plan_reset, etc #include "I2SOut.h" // i2s_out_reset #include "Grbl.h" // user_defined_homing... Implemented in Limits. +#include "Platform.h" // WEAK_LINK // M_PI is not defined in standard C/C++ but some compilers // support it anyway. The following suppresses Intellisense @@ -119,21 +120,21 @@ void mc_cancel_jog() { } } -bool __attribute__((weak)) cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { +bool WEAK_LINK cartesian_to_motors(float* target, plan_line_data_t* pl_data, float* position) { return mc_line(target, pl_data); } -bool __attribute__((weak)) kinematics_pre_homing(AxisMask cycle_mask) { +bool WEAK_LINK kinematics_pre_homing(AxisMask cycle_mask) { return false; // finish normal homing cycle } -void __attribute__((weak)) kinematics_post_homing() {} +void WEAK_LINK kinematics_post_homing() {} -void __attribute__((weak)) motors_to_cartesian(float* cartesian, float* motors, int n_axis) { +void WEAK_LINK motors_to_cartesian(float* cartesian, float* motors, int n_axis) { memcpy(cartesian, motors, n_axis * sizeof(motors[0])); } -void __attribute__((weak)) forward_kinematics(float* position) {} +void WEAK_LINK forward_kinematics(float* position) {} // Execute an arc in offset mode format. position == current xyz, target == target xyz, // offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is // the direction of helical travel, radius == circle radius, isclockwise boolean. Used diff --git a/Grbl_Esp32/src/Motors/Dynamixel2.cpp b/Grbl_Esp32/src/Motors/Dynamixel2.cpp index eaa603cb..055dd988 100644 --- a/Grbl_Esp32/src/Motors/Dynamixel2.cpp +++ b/Grbl_Esp32/src/Motors/Dynamixel2.cpp @@ -30,6 +30,8 @@ #include "../Report.h" // info_serial #include "../Limits.h" // limitsMinPosition +#include + namespace Motors { bool Motors::Dynamixel2::_uart_started = false; uint8_t Motors::Dynamixel2::ids[MAX_N_AXIS][2] = { { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 }, { 0, 0 } }; diff --git a/Grbl_Esp32/src/Motors/Motor.cpp b/Grbl_Esp32/src/Motors/Motor.cpp index 641af48f..7ed35f43 100644 --- a/Grbl_Esp32/src/Motors/Motor.cpp +++ b/Grbl_Esp32/src/Motors/Motor.cpp @@ -41,10 +41,10 @@ namespace Motors { uint8_t Motor::axis_index() const { Assert(config != nullptr && config->_axes != nullptr, "Expected machine to be configured before this is called."); - return config->_axes->findAxisIndex(this); + return uint8_t(config->_axes->findAxisIndex(this)); } uint8_t Motor::dual_axis_index() const { Assert(config != nullptr && config->_axes != nullptr, "Expected machine to be configured before this is called."); - return config->_axes->findAxisGanged(this); + return uint8_t(config->_axes->findAxisGanged(this)); } } diff --git a/Grbl_Esp32/src/Pins/DebugPinDetail.cpp b/Grbl_Esp32/src/Pins/DebugPinDetail.cpp index 4476ea6a..8b6326e6 100644 --- a/Grbl_Esp32/src/Pins/DebugPinDetail.cpp +++ b/Grbl_Esp32/src/Pins/DebugPinDetail.cpp @@ -18,10 +18,11 @@ #include "DebugPinDetail.h" -#include "../Grbl.h" // for printf -#include // for timer -#include // HW serial -#include // vsnprintf +#include "../Grbl.h" // for printf +#include "../Uart.h" +#include // for timer +#include // vsnprintf +#include namespace Pins { inline void WriteSerial(const char* format, ...) { @@ -32,9 +33,9 @@ namespace Pins { va_copy(copy, arg); size_t len = vsnprintf(buf, 50, format, arg); va_end(copy); - Serial.print("[MSG: "); - Serial.print(buf); - Serial.println(" ]"); + Uart0.print("[MSG: "); + Uart0.print(buf); + Uart0.println(" ]"); va_end(arg); } diff --git a/Grbl_Esp32/src/Platform.h b/Grbl_Esp32/src/Platform.h new file mode 100644 index 00000000..ca19f085 --- /dev/null +++ b/Grbl_Esp32/src/Platform.h @@ -0,0 +1,13 @@ +#pragma once + +// This contains definitions of "very platform specific defines", that cannot be dealth with some other way. + +#ifdef ESP32 + +# define WEAK_LINK __attribute__((weak)) + +#else + +# define WEAK_LINK + +#endif diff --git a/Grbl_Esp32/src/Report.cpp b/Grbl_Esp32/src/Report.cpp index 9abd4cb3..e9652ce5 100644 --- a/Grbl_Esp32/src/Report.cpp +++ b/Grbl_Esp32/src/Report.cpp @@ -64,6 +64,7 @@ #include #include #include +#include #ifdef DEBUG_REPORT_HEAP EspClass esp; diff --git a/Grbl_Esp32/src/Settings.cpp b/Grbl_Esp32/src/Settings.cpp index 57ee0464..24f81a82 100644 --- a/Grbl_Esp32/src/Settings.cpp +++ b/Grbl_Esp32/src/Settings.cpp @@ -10,7 +10,10 @@ #include #include #include -#include + +#ifdef ENABLE_WIFI +# include +#endif bool anyState() { return false; diff --git a/Grbl_Esp32/src/Spindles/HuanyangSpindle.cpp b/Grbl_Esp32/src/Spindles/HuanyangSpindle.cpp index 16fedf5a..562b3e05 100644 --- a/Grbl_Esp32/src/Spindles/HuanyangSpindle.cpp +++ b/Grbl_Esp32/src/Spindles/HuanyangSpindle.cpp @@ -149,6 +149,8 @@ #include "HuanyangSpindle.h" +#include // std::max + namespace Spindles { Huanyang::Huanyang() : VFD() { // Baud rate is set in the PD164 setting. If it is not 9600, add, for example, diff --git a/Grbl_Esp32/src/Spindles/Spindle.cpp b/Grbl_Esp32/src/Spindles/Spindle.cpp index 09b7f022..6a05e94a 100644 --- a/Grbl_Esp32/src/Spindles/Spindle.cpp +++ b/Grbl_Esp32/src/Spindles/Spindle.cpp @@ -141,7 +141,7 @@ namespace Spindles { return dev_speed; } void Spindle::spinDelay(SpindleState state, SpindleSpeed speed) { - uint up = 0, down = 0; + uint32_t up = 0, down = 0; switch (state) { case SpindleState::Unknown: // Unknown is only used for an initializer value, diff --git a/Grbl_Esp32/src/Spindles/YL620Spindle.cpp b/Grbl_Esp32/src/Spindles/YL620Spindle.cpp index 291117c2..e28f2550 100644 --- a/Grbl_Esp32/src/Spindles/YL620Spindle.cpp +++ b/Grbl_Esp32/src/Spindles/YL620Spindle.cpp @@ -1,5 +1,3 @@ -#include "YL620Spindle.h" - /* YL620Spindle.cpp @@ -84,6 +82,10 @@ b11: reserved */ +#include "YL620Spindle.h" + +#include + namespace Spindles { YL620::YL620() : VFD() {} diff --git a/Grbl_Esp32/src/Uart.h b/Grbl_Esp32/src/Uart.h index c05de327..b5644345 100644 --- a/Grbl_Esp32/src/Uart.h +++ b/Grbl_Esp32/src/Uart.h @@ -23,6 +23,7 @@ #include "Configuration/Configurable.h" #include "UartTypes.h" +#include #include // TickType_T class Uart : public Stream, public Configuration::Configurable { diff --git a/Grbl_Esp32/src/WebUI/Commands.cpp b/Grbl_Esp32/src/WebUI/Commands.cpp index 44e9d711..6277c32b 100644 --- a/Grbl_Esp32/src/WebUI/Commands.cpp +++ b/Grbl_Esp32/src/WebUI/Commands.cpp @@ -21,6 +21,9 @@ #include "Authentication.h" // MAX_LOCAL_PASSWORD_LENGTH +#include +#include + #ifdef __cplusplus extern "C" { #endif diff --git a/Grbl_Esp32/src/WebUI/WebSettings.cpp b/Grbl_Esp32/src/WebUI/WebSettings.cpp index cc0a2397..c2c71489 100644 --- a/Grbl_Esp32/src/WebUI/WebSettings.cpp +++ b/Grbl_Esp32/src/WebUI/WebSettings.cpp @@ -29,6 +29,7 @@ #include "../Grbl.h" //GRBL_VERSION #include "../Serial.h" // CLIENT_ALL #include "../Report.h" // info_all +#include "Commands.h" // COMMANDS::wait(1); #include "WifiConfig.h" #include "ESPResponse.h" #include "WebServer.h" @@ -36,18 +37,19 @@ #include "TelnetServer.h" // telnet_server #include -#include + +#ifdef ENABLE_WIFI +# include +# include +# include +#endif + #include #include -#include -#include #include namespace WebUI { -#ifdef ENABLE_WIFI -#endif - enum_opt_t onoffOptions = { { "OFF", 0 }, { "ON", 1 } }; static ESPResponseStream* espresponse; @@ -264,7 +266,7 @@ namespace WebUI { while (currentfile.available()) { String currentline = currentfile.readStringUntil('\n'); if (currentline.length() > 0) { - byte line[256]; + uint8_t line[256]; currentline.getBytes(line, 255); err = execute_line((char*)line, client, auth_level); if (err != Error::Ok) { @@ -532,11 +534,13 @@ namespace WebUI { webPrintln("SDK: ", ESP.getSdkVersion()); webPrintln("Flash Size: ", ESPResponseStream::formatBytes(ESP.getFlashChipSize())); +#ifdef ENABLE_WIFI // Round baudRate to nearest 100 because ESP32 can say e.g. 115201 // webPrintln("Baud rate: ", String((Serial.baudRate() / 100) * 100)); // TODO FIXME: Commented out, because we're using Uart webPrintln("Sleep mode: ", WiFi.getSleep() ? "Modem" : "None"); - showWifiStats(); +#endif + if (config->_comms->_bluetoothConfig) { webPrintln(config->_comms->_bluetoothConfig->info().c_str()); } diff --git a/Grbl_Esp32/src/WebUI/WifiConfig.h b/Grbl_Esp32/src/WebUI/WifiConfig.h index 4f488537..6bb69987 100644 --- a/Grbl_Esp32/src/WebUI/WifiConfig.h +++ b/Grbl_Esp32/src/WebUI/WifiConfig.h @@ -24,6 +24,8 @@ #include "../Config.h" // ENABLE_* +#include + #ifndef ENABLE_WIFI namespace WebUI { class WiFiConfig { diff --git a/Grbl_Esp32/test/Pins/Error.cpp b/Grbl_Esp32/test/Pins/ErrorPinTest.cpp similarity index 100% rename from Grbl_Esp32/test/Pins/Error.cpp rename to Grbl_Esp32/test/Pins/ErrorPinTest.cpp diff --git a/UnitTests.vcxproj b/UnitTests.vcxproj index bccd1d32..c2b8b6bc 100644 --- a/UnitTests.vcxproj +++ b/UnitTests.vcxproj @@ -33,61 +33,269 @@ + + - + + + + + + + + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + @@ -96,6 +304,9 @@ + + + diff --git a/UnitTests.vcxproj.filters b/UnitTests.vcxproj.filters index 0b56bb68..3418035f 100644 --- a/UnitTests.vcxproj.filters +++ b/UnitTests.vcxproj.filters @@ -10,24 +10,45 @@ {cc13daa8-4fd4-4995-a724-77db03c229af} - - {2259029a-8770-45f8-889a-f9c25becf189} - - - {a068458b-6148-4377-9d86-41337ee3d689} - {a166a529-634f-48dc-b368-6c03f6f0a36f} {6ae3ae24-fdcd-49f4-9797-a0b0f973c2dc} - - {2b406c50-ba04-4c6d-a21e-0daedeeda9d9} - {1876cb4d-22d0-44a9-907d-4dabd762367e} + + {765754ab-2627-4625-be41-4e49201ad239} + + + {8f8fa64a-6eda-4fd7-8a1a-23d10f603b46} + + + {2d3e3a50-3fe8-4f32-81c2-2128d6d6ad3e} + + + {f39d1497-2e49-4e08-89e4-8926b7a04295} + + + {bb6be066-8250-4ca8-967c-ea9b2e6746c0} + + + {4bf7d2ce-26dc-40f5-8bd4-60c7b4f4ca89} + + + {53e8ad3f-34ef-4802-b6db-6d60ca941a46} + + + {521f05f1-3e07-4301-be76-2a81cdf1f135} + + + {af53d407-844a-47ec-8f6d-de797e13e2db} + + + {1d2d56d1-0078-44c4-be29-447de0ece1e5} + @@ -36,11 +57,140 @@ test - - src + + X86TestSupport - - src + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport\driver + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors src\Pins @@ -57,57 +207,306 @@ src\Pins + + src\Pins + src\Pins src\Pins - - src\StackTrace + + src\Pins + + + src\Pins + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles src\StackTrace - - X86TestSupport + + src\StackTrace - - X86TestSupport + + src\WebUI - - X86TestSupport + + src\WebUI - - src\Pins + + src\WebUI - - src\Configuration + + src\WebUI - - src\Configuration + + src\WebUI - - src\Configuration + + src\WebUI - - src\Configuration + + src\WebUI - - X86TestSupport + + src\WebUI - + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + src src + + src + + + src + + + src + + + src + + + src + src - + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + X86TestSupport\freertos + + + X86TestSupport + + + src + + + X86TestSupport + + + X86TestSupport\freertos + + + X86TestSupport + + X86TestSupport\driver + + X86TestSupport + + + X86TestSupport\freertos + + + X86TestSupport\soc + + + X86TestSupport\soc + + + X86TestSupport\soc + + + X86TestSupport\soc + + + X86TestSupport\soc + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport\TMC + + + X86TestSupport\TMC + + + X86TestSupport\soc + + + X86TestSupport\driver + + + X86TestSupport\driver + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + @@ -116,9 +515,6 @@ test - - test\Pins - test\Pins @@ -128,36 +524,6 @@ test\Pins - - src - - - src\Pins - - - src\Pins - - - src\Pins - - - src\Pins - - - src\Pins - - - src\Pins - - - src\Pins - - - src\StackTrace - - - src\StackTrace - X86TestSupport @@ -173,44 +539,332 @@ test - - src\Pins - test\Configuration - - src\Configuration - - - src\Configuration - test\Configuration test\Configuration - + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Configuration + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Machine + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Motors + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Pins + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\Spindles + + + src\StackTrace + + + src\StackTrace + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src\WebUI + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + src src + + src + + + src + + + src + src + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + src + + + test\Pins + + + X86TestSupport + + + X86TestSupport + + + X86TestSupport + test - - src\StackTrace - + + src\Configuration + src\Configuration + + src\Configuration + + + src\Configuration + + + src\Motors + + + src\Spindles + + + src + + + src + \ No newline at end of file diff --git a/X86TestSupport/Arduino.h b/X86TestSupport/Arduino.h index e1c40c56..84ade2ae 100644 --- a/X86TestSupport/Arduino.h +++ b/X86TestSupport/Arduino.h @@ -2,6 +2,8 @@ #include +#include "esp_err.h" + #define IRAM_ATTR // From Arduino.h: @@ -39,3 +41,128 @@ extern "C" void __pinMode(uint8_t pin, uint8_t mode); extern "C" void __digitalWrite(uint8_t pin, uint8_t val); void delay(int ms); + +// Get time in microseconds since boot. +int64_t esp_timer_get_time(); + +// this_thread::yield? +#define NOP() \ + do { \ + } 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))) + +// 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... + +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); diff --git a/X86TestSupport/FS.cpp b/X86TestSupport/FS.cpp new file mode 100644 index 00000000..843b6d49 --- /dev/null +++ b/X86TestSupport/FS.cpp @@ -0,0 +1,244 @@ +/* + FS.cpp - file system wrapper + Copyright (c) 2015 Ivan Grokhotkov. All rights reserved. + This file is part of the esp8266 core for Arduino environment. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +#include "FS.h" +#include "FSImpl.h" + +using namespace fs; + +size_t File::write(uint8_t c) { + if (!*this) { + return 0; + } + + return _p->write(&c, 1); +} + +time_t File::getLastWrite() { + if (!*this) { + return 0; + } + + return _p->getLastWrite(); +} + +size_t File::write(const uint8_t* buf, size_t size) { + if (!*this) { + return 0; + } + + return _p->write(buf, size); +} + +int File::available() { + if (!*this) { + return false; + } + + return _p->size() - _p->position(); +} + +int File::read() { + if (!*this) { + return -1; + } + + uint8_t result; + if (_p->read(&result, 1) != 1) { + return -1; + } + + return result; +} + +size_t File::read(uint8_t* buf, size_t size) { + if (!*this) { + return -1; + } + + return _p->read(buf, size); +} + +int File::peek() { + if (!*this) { + return -1; + } + + size_t curPos = _p->position(); + int result = read(); + seek(curPos, SeekSet); + return result; +} + +void File::flush() { + if (!*this) { + return; + } + + _p->flush(); +} + +bool File::seek(uint32_t pos, SeekMode mode) { + if (!*this) { + return false; + } + + return _p->seek(pos, mode); +} + +size_t File::position() const { + if (!*this) { + return 0; + } + + return _p->position(); +} + +size_t File::size() const { + if (!*this) { + return 0; + } + + return _p->size(); +} + +void File::close() { + if (_p) { + _p->close(); + _p = nullptr; + } +} + +File::operator bool() const { + return _p != nullptr && *_p != false; +} + +const char* File::path() const { + if (!*this) { + return nullptr; + } + + return _p->path(); +} + +const char* File::name() const { + if (!*this) { + return nullptr; + } + + return _p->name(); +} + +//to implement +bool File::isDirectory(void) { + if (!*this) { + return false; + } + return _p->isDirectory(); +} + +File File::openNextFile(const char* mode) { + if (!*this) { + return File(); + } + return _p->openNextFile(mode); +} + +void File::rewindDirectory(void) { + if (!*this) { + return; + } + _p->rewindDirectory(); +} + +File FS::open(const String& path, const char* mode) { + return open(path.c_str(), mode); +} + +File FS::open(const char* path, const char* mode) { + if (!_impl) { + return File(); + } + + return File(_impl->open(path, mode)); +} + +bool FS::exists(const char* path) { + if (!_impl) { + return false; + } + return _impl->exists(path); +} + +bool FS::exists(const String& path) { + return exists(path.c_str()); +} + +bool FS::remove(const char* path) { + if (!_impl) { + return false; + } + return _impl->remove(path); +} + +bool FS::remove(const String& path) { + return remove(path.c_str()); +} + +bool FS::rename(const char* pathFrom, const char* pathTo) { + if (!_impl) { + return false; + } + return _impl->rename(pathFrom, pathTo); +} + +bool FS::rename(const String& pathFrom, const String& pathTo) { + return rename(pathFrom.c_str(), pathTo.c_str()); +} + +bool FS::mkdir(const char* path) { + if (!_impl) { + return false; + } + return _impl->mkdir(path); +} + +bool FS::mkdir(const String& path) { + return mkdir(path.c_str()); +} + +bool FS::rmdir(const char* path) { + if (!_impl) { + return false; + } + return _impl->rmdir(path); +} + +bool FS::rmdir(const String& path) { + return rmdir(path.c_str()); +} + +void FSImpl::mountpoint(const char* mp) { + _mountpoint = mp; +} + +const char* FSImpl::mountpoint() { + return _mountpoint; +} diff --git a/X86TestSupport/FS.h b/X86TestSupport/FS.h new file mode 100644 index 00000000..11ac14d8 --- /dev/null +++ b/X86TestSupport/FS.h @@ -0,0 +1,107 @@ +/* + FS.h - file system wrapper + Copyright (c) 2015 Ivan Grokhotkov. All rights reserved. + This file is part of the esp8266 core for Arduino environment. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +#ifndef FS_H +#define FS_H + +#include +#include "Stream.h" + +namespace fs { + +#define FILE_READ "r" +#define FILE_WRITE "w" +#define FILE_APPEND "a" + + class File; + + class FileImpl; + typedef std::shared_ptr FileImplPtr; + class FSImpl; + typedef std::shared_ptr FSImplPtr; + + enum SeekMode { SeekSet = 0, SeekCur = 1, SeekEnd = 2 }; + + class File : public Stream { + public: + File(FileImplPtr p = FileImplPtr()) : _p(p) { _timeout = 0; } + + size_t write(uint8_t) override; + size_t write(const uint8_t* buf, size_t size) override; + int available() override; + int read() override; + int peek() override; + void flush() override; + size_t read(uint8_t* buf, size_t size); + size_t readBytes(char* buffer, size_t length) { return read((uint8_t*)buffer, length); } + + bool seek(uint32_t pos, SeekMode mode); + bool seek(uint32_t pos) { return seek(pos, SeekSet); } + size_t position() const; + size_t size() const; + void close(); + operator bool() const; + time_t getLastWrite(); + const char* path() const; + const char* name() const; + + bool isDirectory(void); + File openNextFile(const char* mode = FILE_READ); + void rewindDirectory(void); + + protected: + FileImplPtr _p; + }; + + class FS { + public: + FS(FSImplPtr impl) : _impl(impl) {} + + File open(const char* path, const char* mode = FILE_READ); + File open(const String& path, const char* mode = FILE_READ); + + bool exists(const char* path); + bool exists(const String& path); + + bool remove(const char* path); + bool remove(const String& path); + + bool rename(const char* pathFrom, const char* pathTo); + bool rename(const String& pathFrom, const String& pathTo); + + bool mkdir(const char* path); + bool mkdir(const String& path); + + bool rmdir(const char* path); + bool rmdir(const String& path); + + protected: + FSImplPtr _impl; + }; + +} // namespace fs + +#ifndef FS_NO_GLOBALS +using fs::File; +using fs::FS; +using fs::SeekCur; +using fs::SeekEnd; +using fs::SeekMode; +using fs::SeekSet; +#endif //FS_NO_GLOBALS + +#endif //FS_H diff --git a/X86TestSupport/FSImpl.h b/X86TestSupport/FSImpl.h new file mode 100644 index 00000000..5956eb62 --- /dev/null +++ b/X86TestSupport/FSImpl.h @@ -0,0 +1,66 @@ +/* + FSImpl.h - base file system interface + Copyright (c) 2015 Ivan Grokhotkov. All rights reserved. + This file is part of the esp8266 core for Arduino environment. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ +#ifndef FSIMPL_H +#define FSIMPL_H + +#include +#include + +namespace fs { + + class FileImpl { + public: + virtual ~FileImpl() {} + virtual size_t write(const uint8_t* buf, size_t size) = 0; + virtual size_t read(uint8_t* buf, size_t size) = 0; + virtual void flush() = 0; + virtual bool seek(uint32_t pos, SeekMode mode) = 0; + virtual size_t position() const = 0; + virtual size_t size() const = 0; + virtual void close() = 0; + virtual time_t getLastWrite() = 0; + virtual const char* path() const = 0; + virtual const char* name() const = 0; + virtual bool isDirectory(void) = 0; + virtual FileImplPtr openNextFile(const char* mode) = 0; + virtual void rewindDirectory(void) = 0; + virtual operator bool() = 0; + }; + + class FSImpl { + protected: + const char* _mountpoint; + + public: + FSImpl() : _mountpoint(NULL) {} + virtual ~FSImpl() {} + virtual FileImplPtr open(const char* path, const char* mode) = 0; + virtual bool exists(const char* path) = 0; + virtual bool rename(const char* pathFrom, const char* pathTo) = 0; + virtual bool remove(const char* path) = 0; + virtual bool mkdir(const char* path) = 0; + virtual bool rmdir(const char* path) = 0; + void mountpoint(const char*); + const char* mountpoint(); + }; + +} // namespace fs + +#endif //FSIMPL_H diff --git a/X86TestSupport/Print.cpp b/X86TestSupport/Print.cpp new file mode 100644 index 00000000..61edf179 --- /dev/null +++ b/X86TestSupport/Print.cpp @@ -0,0 +1,331 @@ +/* + Print.cpp - Base class that provides print() and println() + Copyright (c) 2008 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + Modified 23 November 2006 by David A. Mellis + Modified December 2014 by Ivan Grokhotkov + Modified May 2015 by Michael C. Miller - ESP31B progmem support + */ + +#include +#include +#include +#include +#include +#include "Arduino.h" + +#include "Print.h" +extern "C" { +#include "time.h" +} + +// Public Methods ////////////////////////////////////////////////////////////// + +/* default implementation: may be overridden */ +size_t Print::write(const uint8_t* buffer, size_t size) { + size_t n = 0; + while (size--) { + n += write(*buffer++); + } + return n; +} + +size_t Print::printf(const char* format, ...) { + char loc_buf[64]; + char* temp = loc_buf; + va_list arg; + va_list copy; + va_start(arg, format); + va_copy(copy, arg); + int len = vsnprintf(temp, sizeof(loc_buf), format, copy); + va_end(copy); + if (len < 0) { + va_end(arg); + return 0; + }; + if (len >= sizeof(loc_buf)) { + temp = (char*)malloc(len + 1); + if (temp == NULL) { + va_end(arg); + return 0; + } + len = vsnprintf(temp, len + 1, format, arg); + } + va_end(arg); + len = write((uint8_t*)temp, len); + if (temp != loc_buf) { + free(temp); + } + return len; +} + +size_t Print::print(const String& s) { + return write(s.c_str(), s.length()); +} + +size_t Print::print(const char str[]) { + return write(str); +} + +size_t Print::print(char c) { + return write(c); +} + +size_t Print::print(unsigned char b, int base) { + return print((unsigned long)b, base); +} + +size_t Print::print(int n, int base) { + return print((long)n, base); +} + +size_t Print::print(unsigned int n, int base) { + return print((unsigned long)n, base); +} + +size_t Print::print(long n, int base) { + int t = 0; + if (base == 10 && n < 0) { + t = print('-'); + n = -n; + } + return printNumber(static_cast(n), base) + t; +} + +size_t Print::print(unsigned long n, int base) { + if (base == 0) { + return write(n); + } else { + return printNumber(n, base); + } +} + +size_t Print::print(long long n, int base) { + int t = 0; + if (base == 10 && n < 0) { + t = print('-'); + n = -n; + } + return printNumber(static_cast(n), base) + t; +} + +size_t Print::print(unsigned long long n, int base) { + if (base == 0) { + return write(n); + } else { + return printNumber(n, base); + } +} + +size_t Print::print(double n, int digits) { + return printFloat(n, digits); +} + +size_t Print::print(const Printable& x) { + return x.printTo(*this); +} + +size_t Print::print(struct tm* timeinfo, const char* format) { + const char* f = format; + if (!f) { + f = "%c"; + } + char buf[64]; + size_t written = strftime(buf, 64, f, timeinfo); + if (written == 0) { + return written; + } + return print(buf); +} + +size_t Print::println(void) { + return print("\r\n"); +} + +size_t Print::println(const String& s) { + size_t n = print(s); + n += println(); + return n; +} + +size_t Print::println(const char c[]) { + size_t n = print(c); + n += println(); + return n; +} + +size_t Print::println(char c) { + size_t n = print(c); + n += println(); + return n; +} + +size_t Print::println(unsigned char b, int base) { + size_t n = print(b, base); + n += println(); + return n; +} + +size_t Print::println(int num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(unsigned int num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(long num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(unsigned long num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(long long num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(unsigned long long num, int base) { + size_t n = print(num, base); + n += println(); + return n; +} + +size_t Print::println(double num, int digits) { + size_t n = print(num, digits); + n += println(); + return n; +} + +size_t Print::println(const Printable& x) { + size_t n = print(x); + n += println(); + return n; +} + +size_t Print::println(struct tm* timeinfo, const char* format) { + size_t n = print(timeinfo, format); + n += println(); + return n; +} + +// Private Methods ///////////////////////////////////////////////////////////// + +size_t Print::printNumber(unsigned long n, uint8_t base) { + char buf[8 * sizeof(n) + 1]; // Assumes 8-bit chars plus zero byte. + char* str = &buf[sizeof(buf) - 1]; + + *str = '\0'; + + // prevent crash if called with base == 1 + if (base < 2) { + base = 10; + } + + do { + char c = n % base; + n /= base; + + *--str = c < 10 ? c + '0' : c + 'A' - 10; + } while (n); + + return write(str); +} + +size_t Print::printNumber(unsigned long long n, uint8_t base) { + char buf[8 * sizeof(n) + 1]; // Assumes 8-bit chars plus zero byte. + char* str = &buf[sizeof(buf) - 1]; + + *str = '\0'; + + // prevent crash if called with base == 1 + if (base < 2) { + base = 10; + } + + do { + auto m = n; + n /= base; + char c = m - base * n; + + *--str = c < 10 ? c + '0' : c + 'A' - 10; + } while (n); + + return write(str); +} + +size_t Print::printFloat(double number, uint8_t digits) { + size_t n = 0; + + if (isnan(number)) { + return print("nan"); + } + if (isinf(number)) { + return print("inf"); + } + if (number > 4294967040.0) { + return print("ovf"); // constant determined empirically + } + if (number < -4294967040.0) { + return print("ovf"); // constant determined empirically + } + + // Handle negative numbers + if (number < 0.0) { + n += print('-'); + number = -number; + } + + // Round correctly so that print(1.999, 2) prints as "2.00" + double rounding = 0.5; + for (uint8_t i = 0; i < digits; ++i) { + rounding /= 10.0; + } + + number += rounding; + + // Extract the integer part of the number and print it + unsigned long int_part = (unsigned long)number; + double remainder = number - (double)int_part; + n += print(int_part); + + // Print the decimal point, but only if there are digits beyond + if (digits > 0) { + n += print("."); + } + + // Extract digits from the remainder one at a time + while (digits-- > 0) { + remainder *= 10.0; + int toPrint = int(remainder); + n += print(toPrint); + remainder -= toPrint; + } + + return n; +} diff --git a/X86TestSupport/Print.h b/X86TestSupport/Print.h new file mode 100644 index 00000000..158e2e58 --- /dev/null +++ b/X86TestSupport/Print.h @@ -0,0 +1,93 @@ +/* + Print.h - Base class that provides print() and println() + Copyright (c) 2008 David A. Mellis. All right reserved. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +#ifndef Print_h +#define Print_h + +#include +#include + +#include "WString.h" +#include "Printable.h" + +#define DEC 10 +#define HEX 16 +#define OCT 8 +#define BIN 2 + +class Print { +private: + int write_error; + size_t printNumber(unsigned long, uint8_t); + size_t printNumber(unsigned long long, uint8_t); + size_t printFloat(double, uint8_t); + +protected: + void setWriteError(int err = 1) { write_error = err; } + +public: + Print() : write_error(0) {} + virtual ~Print() {} + int getWriteError() { return write_error; } + void clearWriteError() { setWriteError(0); } + + virtual size_t write(uint8_t) = 0; + size_t write(const char* str) { + if (str == NULL) { + return 0; + } + return write((const uint8_t*)str, strlen(str)); + } + virtual size_t write(const uint8_t* buffer, size_t size); + size_t write(const char* buffer, size_t size) { return write((const uint8_t*)buffer, size); } + + size_t printf(const char* format, ...); + + // add availableForWrite to make compatible with Arduino Print.h + // default to zero, meaning "a single write may block" + // should be overriden by subclasses with buffering + virtual int availableForWrite() { return 0; } + size_t print(const String&); + size_t print(const char[]); + size_t print(char); + size_t print(unsigned char, int = DEC); + size_t print(int, int = DEC); + size_t print(unsigned int, int = DEC); + size_t print(long, int = DEC); + size_t print(unsigned long, int = DEC); + size_t print(long long, int = DEC); + size_t print(unsigned long long, int = DEC); + size_t print(double, int = 2); + size_t print(const Printable&); + size_t print(struct tm* timeinfo, const char* format = NULL); + + size_t println(const String& s); + size_t println(const char[]); + size_t println(char); + size_t println(unsigned char, int = DEC); + size_t println(int, int = DEC); + size_t println(unsigned int, int = DEC); + size_t println(long, int = DEC); + size_t println(unsigned long, int = DEC); + size_t println(long long, int = DEC); + size_t println(unsigned long long, int = DEC); + size_t println(double, int = 2); + size_t println(const Printable&); + size_t println(struct tm* timeinfo, const char* format = NULL); + size_t println(void); +}; + +#endif diff --git a/X86TestSupport/Printable.h b/X86TestSupport/Printable.h new file mode 100644 index 00000000..7cde2030 --- /dev/null +++ b/X86TestSupport/Printable.h @@ -0,0 +1,36 @@ +/* + Printable.h - Interface class that allows printing of complex types + Copyright (c) 2011 Adrian McEwen. All right reserved. + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + */ + +#ifndef Printable_h +#define Printable_h + +#include + +class Print; + +/** The Printable class provides a way for new classes to allow themselves to be printed. + By deriving from Printable and implementing the printTo method, it will then be possible + for users to print out instances of this class by passing them into the usual + Print::print and Print::println methods. + */ + +class Printable { +public: + virtual ~Printable() {} + virtual size_t printTo(Print& p) const = 0; +}; + +#endif diff --git a/X86TestSupport/SD.h b/X86TestSupport/SD.h new file mode 100644 index 00000000..f14452ef --- /dev/null +++ b/X86TestSupport/SD.h @@ -0,0 +1,51 @@ +// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef _SD_H_ +#define _SD_H_ + +#include "FS.h" +#include "SPI.h" + +namespace fs { + + class SDFS : public FS { + protected: + uint8_t _pdrv; + + public: + SDFS(FSImplPtr impl); + bool begin(uint8_t ssPin, + SPIClass& spi = SPI, + uint32_t frequency = 4000000, + const char* mountpoint = "/sd", + uint8_t max_files = 5, + bool format_if_empty = false); + void end(); + uint64_t cardSize(); + uint64_t totalBytes(); + uint64_t usedBytes(); + bool readRAW(uint8_t* buffer, uint32_t sector); + bool writeRAW(uint8_t* buffer, uint32_t sector); + }; + +} + +extern fs::SDFS SD; + +using namespace fs; +typedef fs::File SDFile; +typedef fs::SDFS SDFileSystemClass; +#define SDFileSystem SD + +#endif /* _SD_H_ */ diff --git a/X86TestSupport/SPI.h b/X86TestSupport/SPI.h new file mode 100644 index 00000000..c0cf82eb --- /dev/null +++ b/X86TestSupport/SPI.h @@ -0,0 +1,9 @@ +#pragma once + +class SPIClass { +public: + void begin(int sck, int miso, int mosi, int ss) { /* TODO */ + } +}; + +extern SPIClass SPI; diff --git a/X86TestSupport/SPIFFS.h b/X86TestSupport/SPIFFS.h new file mode 100644 index 00000000..853b2e0c --- /dev/null +++ b/X86TestSupport/SPIFFS.h @@ -0,0 +1,40 @@ +// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef _SPIFFS_H_ +#define _SPIFFS_H_ + +#include "FS.h" + +namespace fs { + + class SPIFFSFS : public FS { + public: + SPIFFSFS(); + ~SPIFFSFS(); + bool begin(bool formatOnFail = false, const char* basePath = "/spiffs", uint8_t maxOpenFiles = 10, const char* partitionLabel = NULL); + bool format(); + size_t totalBytes(); + size_t usedBytes(); + void end(); + + private: + char* partitionLabel_; + }; + +} + +extern fs::SPIFFSFS SPIFFS; + +#endif diff --git a/X86TestSupport/Stream.cpp b/X86TestSupport/Stream.cpp new file mode 100644 index 00000000..8eeb41fd --- /dev/null +++ b/X86TestSupport/Stream.cpp @@ -0,0 +1,323 @@ +/* + Stream.cpp - adds parsing methods to Stream class + Copyright (c) 2008 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + Created July 2011 + parsing functions based on TextFinder library by Michael Margolis + */ + +#include "Arduino.h" +#include "Stream.h" + +#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 + +/* +// private method to read stream with timeout +int Stream::timedRead() { + int c; + _startMillis = millis(); + do { + c = read(); + if (c >= 0) { + return c; + } + } while (millis() - _startMillis < _timeout); + return -1; // -1 indicates timeout +} + +// private method to peek stream with timeout +int Stream::timedPeek() { + int c; + _startMillis = millis(); + do { + c = peek(); + if (c >= 0) { + return c; + } + } while (millis() - _startMillis < _timeout); + return -1; // -1 indicates timeout +} +*/ + +// returns peek of the next digit in the stream or -1 if timeout +// discards non-numeric characters +int Stream::peekNextDigit() { + int c; + while (1) { + c = timedPeek(); + if (c < 0) { + return c; // timeout + } + if (c == '-') { + return c; + } + if (c >= '0' && c <= '9') { + return c; + } + read(); // discard non-numeric + } +} + +// Public Methods +////////////////////////////////////////////////////////////// + +void Stream::setTimeout(unsigned long timeout) // sets the maximum number of milliseconds to wait +{ + _timeout = timeout; +} +unsigned long Stream::getTimeout(void) { + return _timeout; +} + +// find returns true if the target string is found +bool Stream::find(const char* target) { + return findUntil(target, strlen(target), NULL, 0); +} + +// 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 +bool Stream::find(const char* target, size_t length) { + return findUntil(target, length, NULL, 0); +} + +// as find but search ends if the terminator string is found +bool Stream::findUntil(const char* target, const char* terminator) { + return findUntil(target, strlen(target), terminator, strlen(terminator)); +} +/* +// reads data from the stream until the target string of the given length is found +// search terminated if the terminator string is found +// returns true if target string is found, false if terminated or timed out +bool Stream::findUntil(const char* target, size_t targetLen, const char* terminator, size_t termLen) { + if (terminator == NULL) { + MultiTarget t[1] = { { target, targetLen, 0 } }; + return findMulti(t, 1) == 0 ? true : false; + } else { + MultiTarget t[2] = { { target, targetLen, 0 }, { terminator, termLen, 0 } }; + return findMulti(t, 2) == 0 ? true : false; + } +} + +int Stream::findMulti(struct Stream::MultiTarget* targets, int tCount) { + // any zero length target string automatically matches and would make + // a mess of the rest of the algorithm. + for (struct MultiTarget* t = targets; t < targets + tCount; ++t) { + if (t->len <= 0) + return t - targets; + } + + while (1) { + int c = timedRead(); + if (c < 0) + return -1; + + for (struct MultiTarget* t = targets; t < targets + tCount; ++t) { + // the simple case is if we match, deal with that first. + if (c == t->str[t->index]) { + if (++t->index == t->len) + return t - targets; + else + continue; + } + + // if not we need to walk back and see if we could have matched further + // down the stream (ie '1112' doesn't match the first position in '11112' + // but it will match the second position so we can't just reset the current + // index to 0 when we find a mismatch. + if (t->index == 0) + continue; + + int origIndex = t->index; + do { + --t->index; + // first check if current char works against the new current index + if (c != t->str[t->index]) + continue; + + // if it's the only char then we're good, nothing more to check + if (t->index == 0) { + t->index++; + break; + } + + // otherwise we need to check the rest of the found string + int diff = origIndex - t->index; + size_t i; + for (i = 0; i < t->index; ++i) { + if (t->str[i] != t->str[i + diff]) + break; + } + + // if we successfully got through the previous loop then our current + // index is good. + if (i == t->index) { + t->index++; + break; + } + + // otherwise we just try the next index + } while (t->index); + } + } + // unreachable + return -1; +} +*/ + +// returns the first valid (long) integer value from the current position. +// initial characters that are not digits (or the minus sign) are skipped +// function is terminated by the first character that is not a digit. +long Stream::parseInt() { + return parseInt(NO_SKIP_CHAR); // terminate on first non-digit character (or timeout) +} + +// as above but a given skipChar is ignored +// this allows format characters (typically commas) in values to be ignored +long Stream::parseInt(char skipChar) { + bool isNegative = false; + long value = 0; + int c; + + c = peekNextDigit(); + // ignore non numeric leading characters + if (c < 0) { + return 0; // zero returned if timeout + } + + do { + if (c == skipChar) { + } // ignore this charactor + else if (c == '-') { + isNegative = true; + } else if (c >= '0' && c <= '9') { // is c a digit? + value = value * 10 + c - '0'; + } + read(); // consume the character we got with peek + c = timedPeek(); + } while ((c >= '0' && c <= '9') || c == skipChar); + + if (isNegative) { + value = -value; + } + return value; +} + +// as parseInt but returns a floating point value +float Stream::parseFloat() { + return parseFloat(NO_SKIP_CHAR); +} + +// as above but the given skipChar is ignored +// this allows format characters (typically commas) in values to be ignored +float Stream::parseFloat(char skipChar) { + bool isNegative = false; + bool isFraction = false; + long value = 0; + int c; + float fraction = 1.0; + + c = peekNextDigit(); + // ignore non numeric leading characters + if (c < 0) { + return 0; // zero returned if timeout + } + + do { + if (c == skipChar) { + } // ignore + else if (c == '-') { + isNegative = true; + } else if (c == '.') { + isFraction = true; + } else if (c >= '0' && c <= '9') { // is c a digit? + value = value * 10 + c - '0'; + if (isFraction) { + fraction *= 0.1; + } + } + read(); // consume the character we got with peek + c = timedPeek(); + } while ((c >= '0' && c <= '9') || c == '.' || c == skipChar); + + if (isNegative) { + value = -value; + } + if (isFraction) { + return value * fraction; + } else { + return value; + } +} + +// read characters from stream into buffer +// terminates if length characters have been read, or timeout (see setTimeout) +// returns the number of characters placed in the buffer +// the buffer is NOT null terminated. +// +size_t Stream::readBytes(char* buffer, size_t length) { + size_t count = 0; + while (count < length) { + int c = timedRead(); + if (c < 0) { + break; + } + *buffer++ = (char)c; + count++; + } + return count; +} + +// as readBytes with terminator character +// terminates if length characters have been read, timeout, or if the terminator character detected +// returns the number of characters placed in the buffer (0 means no valid data found) + +size_t Stream::readBytesUntil(char terminator, char* buffer, size_t length) { + if (length < 1) { + return 0; + } + size_t index = 0; + while (index < length) { + int c = timedRead(); + if (c < 0 || c == terminator) { + break; + } + *buffer++ = (char)c; + index++; + } + return index; // return number of characters, not including null terminator +} + +String Stream::readString() { + String ret; + int c = timedRead(); + while (c >= 0) { + ret += (char)c; + c = timedRead(); + } + return ret; +} + +String Stream::readStringUntil(char terminator) { + String ret; + int c = timedRead(); + while (c >= 0 && c != terminator) { + ret += (char)c; + c = timedRead(); + } + return ret; +} diff --git a/X86TestSupport/Stream.h b/X86TestSupport/Stream.h new file mode 100644 index 00000000..948869cb --- /dev/null +++ b/X86TestSupport/Stream.h @@ -0,0 +1,108 @@ +/* + Stream.h - base class for character-based streams. + Copyright (c) 2010 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + + parsing functions based on TextFinder library by Michael Margolis + */ + +#ifndef Stream_h +#define Stream_h + +#include +#include "Print.h" + +// compatability macros for testing +/* + #define getInt() parseInt() + #define getInt(skipChar) parseInt(skipchar) + #define getFloat() parseFloat() + #define getFloat(skipChar) parseFloat(skipChar) + #define getString( pre_string, post_string, buffer, length) + readBytesBetween( pre_string, terminator, buffer, length) + */ + +class Stream : public Print { +protected: + unsigned long _timeout; // number of milliseconds to wait for the next char before aborting timed read + unsigned long _startMillis; // used for timeout measurement + int timedRead(); // private method to read stream with timeout + int timedPeek(); // private method to peek stream with timeout + int peekNextDigit(); // returns the next numeric digit in the stream or -1 if timeout + +public: + virtual int available() = 0; + virtual int read() = 0; + virtual int peek() = 0; + virtual void flush() = 0; + + Stream() : _startMillis(0) { _timeout = 1000; } + virtual ~Stream() {} + + // parsing methods + + void setTimeout(unsigned long timeout); // sets maximum milliseconds to wait for stream data, default is 1 second + unsigned long getTimeout(void); + bool find(const char* target); // reads data from the stream until the target string is found + bool find(uint8_t* target) { return find((char*)target); } + // returns true if target string is found, false if timed out (see setTimeout) + + bool find(const char* target, size_t length); // reads data from the stream until the target string of given length is found + bool find(const uint8_t* target, size_t length) { return find((char*)target, length); } + // returns true if target string is found, false if timed out + + 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 uint8_t* target, const char* terminator) { return findUntil((char*)target, terminator); } + + bool findUntil(const char* target, + size_t targetLen, + const char* terminate, + size_t termLen); // as above but search ends if the terminate string is found + bool findUntil(const uint8_t* target, size_t targetLen, const char* terminate, size_t termLen) { + return findUntil((char*)target, targetLen, terminate, termLen); + } + + 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 + // integer is terminated by the first character that is not a digit. + + float parseFloat(); // float version of parseInt + + virtual size_t readBytes(char* buffer, size_t length); // read chars from stream into buffer + virtual size_t readBytes(uint8_t* buffer, size_t length) { return readBytes((char*)buffer, length); } + // terminates if length characters have been read or timeout (see setTimeout) + // returns the number of characters placed in the buffer (0 means no valid data found) + + size_t readBytesUntil(char terminator, char* buffer, size_t length); // as readBytes with terminator character + size_t readBytesUntil(char terminator, uint8_t* buffer, size_t length) { return readBytesUntil(terminator, (char*)buffer, length); } + // terminates if length characters have been read, timeout, or if the terminator character detected + // returns the number of characters placed in the buffer (0 means no valid data found) + + // Arduino String functions to be added here + virtual String readString(); + String readStringUntil(char terminator); + +protected: + long parseInt(char skipChar); // as above but the given skipChar is ignored + // as above but the given skipChar is ignored + // this allows format characters (typically commas) in values to be ignored + + float parseFloat(char skipChar); // as above but the given skipChar is ignored +}; + +#endif diff --git a/X86TestSupport/TMC/TMCStepper.h b/X86TestSupport/TMC/TMCStepper.h new file mode 100644 index 00000000..7f9442f0 --- /dev/null +++ b/X86TestSupport/TMC/TMCStepper.h @@ -0,0 +1,1251 @@ +#pragma once + +//#define TMCDEBUG + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" +#pragma GCC diagnostic ignored "-Wunused-variable" + +#if defined(ARDUINO) && ARDUINO >= 100 + #include +#endif + +#include +#include + +#if (__cplusplus == 201703L) && defined(__has_include) + #define SW_CAPABLE_PLATFORM __has_include() +#elif defined(__AVR__) || defined(TARGET_LPC1768) || defined(ARDUINO_ARCH_STM32) + #define SW_CAPABLE_PLATFORM true +#else + #define SW_CAPABLE_PLATFORM false +#endif + +#if SW_CAPABLE_PLATFORM + #include +#endif + +#include "source/SERIAL_SWITCH.h" +#include "source/SW_SPI.h" + +#pragma GCC diagnostic pop + +#include "source/TMC2130_bitfields.h" +#include "source/TMC2160_bitfields.h" +#include "source/TMC5130_bitfields.h" +#include "source/TMC5160_bitfields.h" +#include "source/TMC2208_bitfields.h" +#include "source/TMC2209_bitfields.h" +#include "source/TMC2660_bitfields.h" + +#define INIT_REGISTER(REG) REG##_t REG##_register = REG##_t +#define INIT2130_REGISTER(REG) TMC2130_n::REG##_t REG##_register = TMC2130_n::REG##_t +#define INIT2160_REGISTER(REG) TMC2160_n::REG##_t REG##_register = TMC2160_n::REG##_t +#define INIT5130_REGISTER(REG) TMC5130_n::REG##_t REG##_register = TMC5130_n::REG##_t +#define INIT5160_REGISTER(REG) TMC5160_n::REG##_t REG##_register = TMC5160_n::REG##_t +#define INIT2660_REGISTER(REG) TMC2660_n::REG##_t REG##_register = TMC2660_n::REG##_t +#define INIT2208_REGISTER(REG) TMC2208_n::REG##_t REG##_register = TMC2208_n::REG##_t +#define INIT2224_REGISTER(REG) TMC2224_n::REG##_t REG##_register = TMC2224_n::REG##_t +#define SET_ALIAS(TYPE, DRIVER, NEW, ARG, OLD) TYPE (DRIVER::*NEW)(ARG) = &DRIVER::OLD + +#define TMCSTEPPER_VERSION 0x000701 // v0.7.1 + +class TMCStepper { + public: + uint16_t cs2rms(uint8_t CS); + void rms_current(uint16_t mA); + void rms_current(uint16_t mA, float mult); + uint16_t rms_current(); + void hold_multiplier(float val) { holdMultiplier = val; } + float hold_multiplier() { return holdMultiplier; } + uint8_t test_connection(); + + // Helper functions + void microsteps(uint16_t ms); + uint16_t microsteps(); + void blank_time(uint8_t value); + uint8_t blank_time(); + void hysteresis_end(int8_t value); + int8_t hysteresis_end(); + void hysteresis_start(uint8_t value); + uint8_t hysteresis_start(); + + // R+WC: GSTAT + void GSTAT( uint8_t input); + uint8_t GSTAT(); + bool reset(); + bool drv_err(); + bool uv_cp(); + + // W: IHOLD_IRUN + void IHOLD_IRUN( uint32_t input); + uint32_t IHOLD_IRUN(); + void ihold( uint8_t B); + void irun( uint8_t B); + void iholddelay( uint8_t B); + uint8_t ihold(); + uint8_t irun(); + uint8_t iholddelay(); + + // W: TPOWERDOWN + uint8_t TPOWERDOWN(); + void TPOWERDOWN( uint8_t input); + + // R: TSTEP + uint32_t TSTEP(); + + // W: TPWMTHRS + uint32_t TPWMTHRS(); + void TPWMTHRS( uint32_t input); + + // R: MSCNT + uint16_t MSCNT(); + + // R: MSCURACT + uint32_t MSCURACT(); + int16_t cur_a(); + int16_t cur_b(); + + protected: + TMCStepper(float RS) : Rsense(RS) {}; + INIT_REGISTER(IHOLD_IRUN){{.sr=0}}; // 32b + INIT_REGISTER(TPOWERDOWN){.sr=0}; // 8b + INIT_REGISTER(TPWMTHRS){.sr=0}; // 32b + + static constexpr uint8_t TMC_READ = 0x00, + TMC_WRITE = 0x80; + + struct TSTEP_t { constexpr static uint8_t address = 0x12; }; + struct MSCNT_t { constexpr static uint8_t address = 0x6A; }; + + virtual void write(uint8_t, uint32_t) = 0; + virtual uint32_t read(uint8_t) = 0; + virtual void vsense(bool) = 0; + virtual bool vsense(void) = 0; + virtual uint32_t DRV_STATUS() = 0; + virtual void hend(uint8_t) = 0; + virtual uint8_t hend() = 0; + virtual void hstrt(uint8_t) = 0; + virtual uint8_t hstrt() = 0; + virtual void mres(uint8_t) = 0; + virtual uint8_t mres() = 0; + virtual void tbl(uint8_t) = 0; + virtual uint8_t tbl() = 0; + + const float Rsense; + float holdMultiplier = 0.5; +}; + +class TMC2130Stepper : public TMCStepper { + public: + TMC2130Stepper(uint16_t pinCS, float RS = default_RS, int8_t link_index = -1); + TMC2130Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + TMC2130Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + void begin(); + void defaults(); + void setSPISpeed(uint32_t speed); + void switchCSpin(bool state); + bool isEnabled(); + void push(); + + // Helper functions + void sg_current_decrease(uint8_t value); + uint8_t sg_current_decrease(); + + // RW: GCONF + uint32_t GCONF(); + void GCONF( uint32_t value); + void I_scale_analog( bool B); + void internal_Rsense( bool B); + void en_pwm_mode( bool B); + void enc_commutation( bool B); + void shaft( bool B); + void diag0_error( bool B); + void diag0_otpw( bool B); + void diag0_stall( bool B); + void diag1_stall( bool B); + void diag1_index( bool B); + void diag1_onstate( bool B); + void diag1_steps_skipped( bool B); + void diag0_int_pushpull( bool B); + void diag1_pushpull( bool B); + void small_hysteresis( bool B); + void stop_enable( bool B); + void direct_mode( bool B); + bool I_scale_analog(); + bool internal_Rsense(); + bool en_pwm_mode(); + bool enc_commutation(); + bool shaft(); + bool diag0_error(); + bool diag0_otpw(); + bool diag0_stall(); + bool diag1_stall(); + bool diag1_index(); + bool diag1_onstate(); + bool diag1_steps_skipped(); + bool diag0_int_pushpull(); + bool diag1_pushpull(); + bool small_hysteresis(); + bool stop_enable(); + bool direct_mode(); + + // R: IOIN + uint32_t IOIN(); + bool step(); + bool dir(); + bool dcen_cfg4(); + bool dcin_cfg5(); + bool drv_enn_cfg6(); + bool dco(); + uint8_t version(); + + // W: TCOOLTHRS + uint32_t TCOOLTHRS(); + void TCOOLTHRS( uint32_t input); + + // W: THIGH + uint32_t THIGH(); + void THIGH( uint32_t input); + + // RW: XDRIRECT + uint32_t XDIRECT(); + void XDIRECT( uint32_t input); + void coil_A( int16_t B); + void coil_B( int16_t B); + int16_t coil_A(); + int16_t coil_B(); + + // W: VDCMIN + uint32_t VDCMIN(); + void VDCMIN( uint32_t input); + + // RW: CHOPCONF + uint32_t CHOPCONF(); + void CHOPCONF( uint32_t value); + void toff( uint8_t B); + void hstrt( uint8_t B); + void hend( uint8_t B); + //void fd( uint8_t B); + void disfdcc( bool B); + void rndtf( bool B); + void chm( bool B); + void tbl( uint8_t B); + void vsense( bool B); + void vhighfs( bool B); + void vhighchm( bool B); + void sync( uint8_t B); + void mres( uint8_t B); + void intpol( bool B); + void dedge( bool B); + void diss2g( bool B); + uint8_t toff(); + uint8_t hstrt(); + uint8_t hend(); + //uint8_t fd(); + bool disfdcc(); + bool rndtf(); + bool chm(); + uint8_t tbl(); + bool vsense(); + bool vhighfs(); + bool vhighchm(); + uint8_t sync(); + uint8_t mres(); + bool intpol(); + bool dedge(); + bool diss2g(); + + // W: COOLCONF + void COOLCONF(uint32_t value); + uint32_t COOLCONF(); + void semin( uint8_t B); + void seup( uint8_t B); + void semax( uint8_t B); + void sedn( uint8_t B); + void seimin( bool B); + void sgt( int8_t B); + void sfilt( bool B); + uint8_t semin(); + uint8_t seup(); + uint8_t semax(); + uint8_t sedn(); + bool seimin(); + int8_t sgt(); + bool sfilt(); + + // W: DCCTRL + void DCCTRL(uint32_t input); + void dc_time(uint16_t input); + void dc_sg(uint8_t input); + uint32_t DCCTRL(); + uint16_t dc_time(); + uint8_t dc_sg(); + + // R: DRV_STATUS + uint32_t DRV_STATUS(); + uint16_t sg_result(); + bool fsactive(); + uint8_t cs_actual(); + bool stallguard(); + bool ot(); + bool otpw(); + bool s2ga(); + bool s2gb(); + bool ola(); + bool olb(); + bool stst(); + + // W: PWMCONF + void PWMCONF( uint32_t value); + uint32_t PWMCONF(); + void pwm_ampl( uint8_t B); + void pwm_grad( uint8_t B); + void pwm_freq( uint8_t B); + void pwm_autoscale( bool B); + void pwm_symmetric( bool B); + void freewheel( uint8_t B); + uint8_t pwm_ampl(); + uint8_t pwm_grad(); + uint8_t pwm_freq(); + bool pwm_autoscale(); + bool pwm_symmetric(); + uint8_t freewheel(); + + // R: PWM_SCALE + uint8_t PWM_SCALE(); + + // W: ENCM_CTRL + uint8_t ENCM_CTRL(); + void ENCM_CTRL( uint8_t input); + void inv( bool B); + void maxspeed( bool B); + bool inv(); + bool maxspeed(); + + // R: LOST_STEPS + uint32_t LOST_STEPS(); + + // Function aliases + + uint8_t status_response; + + protected: + void beginTransaction(); + void endTransaction(); + uint8_t transfer(const uint8_t data); + void transferEmptyBytes(const uint8_t n); + void write(uint8_t addressByte, uint32_t config); + uint32_t read(uint8_t addressByte); + + INIT_REGISTER(GCONF){{.sr=0}}; // 32b + INIT_REGISTER(TCOOLTHRS){.sr=0}; // 32b + INIT_REGISTER(THIGH){.sr=0}; // 32b + INIT_REGISTER(XDIRECT){{.sr=0}}; // 32b + INIT_REGISTER(VDCMIN){.sr=0}; // 32b + INIT_REGISTER(CHOPCONF){{.sr=0}}; // 32b + INIT_REGISTER(COOLCONF){{.sr=0}}; // 32b + INIT_REGISTER(DCCTRL){{.sr = 0}}; // 32b + INIT_REGISTER(PWMCONF){{.sr=0}}; // 32b + INIT_REGISTER(ENCM_CTRL){{.sr=0}};// 8b + + struct IOINT_t { constexpr static uint8_t address = 0x04; }; + struct PWM_SCALE_t { constexpr static uint8_t address = 0x71; }; + struct LOST_STEPS_t { constexpr static uint8_t address = 0x73; }; + struct DRV_STATUS_t { constexpr static uint8_t address = 0X6F; }; + + static uint32_t spi_speed; // Default 2MHz + const uint16_t _pinCS; + SW_SPIClass * TMC_SW_SPI = nullptr; + static constexpr float default_RS = 0.11; + + int8_t link_index; + static int8_t chain_length; +}; + +class TMC2160Stepper : public TMC2130Stepper { + public: + TMC2160Stepper(uint16_t pinCS, float RS = default_RS, int8_t link_index = -1); + TMC2160Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + TMC2160Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + void begin(); + void defaults(); + void push(); + + uint16_t cs2rms(uint8_t CS); + void rms_current(uint16_t mA); + void rms_current(uint16_t mA, float mult); + uint16_t rms_current(); + + // IOIN + uint32_t IOIN(); + bool refl_step(); + bool refr_dir(); + bool encb_dcen_cfg4(); + bool enca_dcin_cfg5(); + bool drv_enn(); + bool dco_cfg6(); + uint8_t version(); + + // W: OTP_PROG + // R: OTP_READ + // RW: FACTORY_CONF + + // W: SHORT_CONF + void SHORT_CONF(uint32_t); + void s2vs_level(uint8_t); + void s2g_level(uint8_t); + void shortfilter(uint8_t); + void shortdelay(bool); + uint32_t SHORT_CONF(); + uint8_t s2vs_level(); + uint8_t s2g_level(); + uint8_t shortfilter(); + bool shortdelay(); + + // W: DRV_CONF + void DRV_CONF(uint32_t); + void bbmtime(uint8_t); + void bbmclks(uint8_t); + void otselect(uint8_t); + void drvstrength(uint8_t); + void filt_isense(uint8_t); + uint32_t DRV_CONF(); + uint8_t bbmtime(); + uint8_t bbmclks(); + uint8_t otselect(); + uint8_t drvstrength(); + uint8_t filt_isense(); + + // W: GLOBAL_SCALER + void GLOBAL_SCALER(uint8_t); + uint8_t GLOBAL_SCALER(); + + // R: OFFSET_READ + uint16_t OFFSET_READ(); + + // W: PWMCONF + void PWMCONF(uint32_t input); + void pwm_ofs(uint8_t B); + void pwm_grad(uint8_t B); + void pwm_freq(uint8_t B); + void pwm_autoscale(bool B); + void pwm_autograd(bool B); + void freewheel(uint8_t B); + void pwm_reg(uint8_t B); + void pwm_lim(uint8_t B); + uint32_t PWMCONF(); + uint8_t pwm_ofs(); + uint8_t pwm_grad(); + uint8_t pwm_freq(); + bool pwm_autoscale(); + bool pwm_autograd(); + uint8_t freewheel(); + uint8_t pwm_reg(); + uint8_t pwm_lim(); + + // R: PWM_SCALE + uint32_t PWM_SCALE(); + uint8_t pwm_scale_sum(); + uint16_t pwm_scale_auto(); + + protected: + using TMC2130Stepper::ENCM_CTRL; + using TMC2130Stepper::pwm_ampl; + using TMC2130Stepper::pwm_symmetric; + + INIT_REGISTER(SHORT_CONF){{.sr=0}}; + INIT_REGISTER(DRV_CONF){{.sr=0}}; + INIT_REGISTER(GLOBAL_SCALER){.sr=0}; + INIT2160_REGISTER(PWMCONF){{.sr=0}}; + + static constexpr float default_RS = 0.075; +}; + +class TMC5130Stepper : public TMC2160Stepper { + public: + TMC5130Stepper(uint16_t pinCS, float RS = default_RS, int8_t link_index = -1); + TMC5130Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + TMC5130Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + + void begin(); + void defaults(); + void push(); + + void rms_current(uint16_t mA) { TMC2130Stepper::rms_current(mA); } + void rms_current(uint16_t mA, float mult) { TMC2130Stepper::rms_current(mA, mult); } + uint16_t rms_current() { return TMC2130Stepper::rms_current(); } + + // R: IFCNT + uint8_t IFCNT(); + // W: SLAVECONF + uint16_t SLAVECONF(); + void SLAVECONF(uint16_t input); + // R: IOIN + uint32_t IOIN(); + bool refl_step(); + bool refr_dir(); + bool encb_dcen_cfg4(); + bool enca_dcin_cfg5(); + bool drv_enn_cfg6(); + bool enc_n_dco(); + bool sd_mode(); + bool swcomp_in(); + uint8_t version(); + + // RW: GCONF + void diag1_poscomp_pushpull(bool B) { diag1_pushpull(B); } + bool diag1_poscomp_pushpull() { return diag1_pushpull(); } + + // RW: SW_MODE + uint32_t SW_MODE(); + void SW_MODE(uint32_t input); + + void stop_l_enable(bool B); + void stop_r_enable(bool B); + void pol_stop_l(bool B); + void pol_stop_r(bool B); + void swap_lr(bool B); + void latch_l_active(bool B); + void latch_l_inactive(bool B); + void latch_r_active(bool B); + void latch_r_inactive(bool B); + void en_latch_encoder(bool B); + void sg_stop(bool B); + void en_softstop(bool B); + + bool stop_r_enable(); + bool pol_stop_l(); + bool pol_stop_r(); + bool swap_lr(); + bool latch_l_active(); + bool latch_l_inactive(); + bool latch_r_active(); + bool latch_r_inactive(); + bool en_latch_encoder(); + bool sg_stop(); + bool en_softstop(); + + // R+C: RAMP_STAT + uint32_t RAMP_STAT(); + bool status_stop_l(); + bool status_stop_r(); + bool status_latch_l(); + bool status_latch_r(); + bool event_stop_l(); + bool event_stop_r(); + bool event_stop_sg(); + bool event_pos_reached(); + bool velocity_reached(); + bool position_reached(); + bool vzero(); + bool t_zerowait_active(); + bool second_move(); + bool status_sg(); + + // RW: ENCMODE + uint32_t ENCMODE(); + void ENCMODE(uint32_t input); + void pol_a(bool B); + void pol_b(bool B); + void pol_n(bool B); + void ignore_ab(bool B); + void clr_cont(bool B); + void clr_once(bool B); + void pos_edge(bool B); + void neg_edge(bool B); + void clr_enc_x(bool B); + void latch_x_act(bool B); + void enc_sel_decimal(bool B); + bool pol_a(); + bool pol_b(); + bool pol_n(); + bool ignore_ab(); + bool clr_cont(); + bool clr_once(); + bool pos_edge(); + bool neg_edge(); + bool clr_enc_x(); + bool latch_x_act(); + bool enc_sel_decimal(); + + // W: OUTPUT + bool TMC_OUTPUT(); + void TMC_OUTPUT(bool input); + // W: X_COMPARE + uint32_t X_COMPARE(); + void X_COMPARE(uint32_t input); + // RW: RAMPMODE + uint8_t RAMPMODE(); + void RAMPMODE(uint8_t input); + // RW: XACTUAL + int32_t XACTUAL(); + void XACTUAL(int32_t input); + // R: VACTUAL + int32_t VACTUAL(); + // W: VSTART + uint32_t VSTART(); + void VSTART(uint32_t input); + // W: A1 + uint16_t A1(); + void A1(uint16_t input); + // W: V1 + uint32_t V1(); + void V1(uint32_t input); + // W: AMAX + uint16_t AMAX(); + void AMAX(uint16_t input); + // W: VMAX + uint32_t VMAX(); + void VMAX(uint32_t input); + // W: DMAX + uint16_t DMAX(); + void DMAX(uint16_t input); + // W: D1 + uint16_t D1(); + void D1(uint16_t input); + // W: VSTOP + uint32_t VSTOP(); + void VSTOP(uint32_t input); + // W: TZEROWAIT + uint16_t TZEROWAIT(); + void TZEROWAIT(uint16_t input); + // RW: XTARGET + int32_t XTARGET(); + void XTARGET(int32_t input); + // R: XLATCH + uint32_t XLATCH(); + // RW: X_ENC + int32_t X_ENC(); + void X_ENC(int32_t input); + // W: ENC_CONST + uint32_t ENC_CONST(); + void ENC_CONST(uint32_t input); + // R: ENC_STATUS + bool ENC_STATUS(); + // R: ENC_LATCH + uint32_t ENC_LATCH(); + + using TMC2130Stepper::ENCM_CTRL; + + using TMC2130Stepper::PWMCONF; + using TMC2130Stepper::pwm_ampl; + using TMC2130Stepper::pwm_grad; + using TMC2130Stepper::pwm_freq; + using TMC2130Stepper::pwm_autoscale; + using TMC2130Stepper::pwm_symmetric; + using TMC2130Stepper::freewheel; + + using TMC2130Stepper::PWM_SCALE; + + protected: + INIT_REGISTER(SLAVECONF){{.sr=0}}; + INIT_REGISTER(OUTPUT){.sr=0}; + INIT_REGISTER(X_COMPARE){.sr=0}; + INIT_REGISTER(RAMPMODE){.sr=0}; + INIT_REGISTER(XACTUAL){.sr=0}; + INIT_REGISTER(VSTART){.sr=0}; + INIT_REGISTER(A1){.sr=0}; + INIT_REGISTER(V1){.sr=0}; + INIT_REGISTER(AMAX){.sr=0}; + INIT_REGISTER(VMAX){.sr=0}; + INIT_REGISTER(DMAX){.sr=0}; + INIT_REGISTER(D1){.sr=0}; + INIT_REGISTER(VSTOP){.sr=0}; + INIT_REGISTER(TZEROWAIT){.sr=0}; + INIT_REGISTER(SW_MODE){{.sr=0}}; + INIT_REGISTER(ENCMODE){{.sr=0}}; + INIT_REGISTER(ENC_CONST){.sr=0}; + + struct IFCNT_t { constexpr static uint8_t address = 0x02; }; // R + struct VACTUAL_t { constexpr static uint8_t address = 0x22; }; // R + struct XTARGET_t { constexpr static uint8_t address = 0x2D; }; // RW + struct XLATCH_t { constexpr static uint8_t address = 0x36; }; // R + struct X_ENC_t { constexpr static uint8_t address = 0x39; }; // RW + struct ENC_STATUS_t { constexpr static uint8_t address = 0x3B; }; // R+C + struct ENC_LATCH_t { constexpr static uint8_t address = 0x3C; }; // R + + /* + INIT_REGISTER(MSLUT0){0}; + INIT_REGISTER(MSLUT1){0}; + INIT_REGISTER(MSLUT2){0}; + INIT_REGISTER(MSLUT3){0}; + INIT_REGISTER(MSLUT4){0}; + INIT_REGISTER(MSLUT5){0}; + INIT_REGISTER(MSLUT6){0}; + INIT_REGISTER(MSLUT7){0}; + INIT_REGISTER(MSLUTSEL){0}; + INIT_REGISTER(MSLUTSTART){0}; + INIT_REGISTER(MSCNT){0}; + INIT_REGISTER(MSCURACT){0}; + */ + + static constexpr float default_RS = 0.15; + + protected: + using TMC2160Stepper::SHORT_CONF; + using TMC2160Stepper::s2vs_level; + using TMC2160Stepper::s2g_level; + using TMC2160Stepper::shortfilter; + using TMC2160Stepper::shortdelay; + using TMC2160Stepper::DRV_CONF; + using TMC2160Stepper::bbmtime; + using TMC2160Stepper::bbmclks; + using TMC2160Stepper::otselect; + using TMC2160Stepper::drvstrength; + using TMC2160Stepper::filt_isense; + using TMC2160Stepper::GLOBAL_SCALER; + using TMC2160Stepper::OFFSET_READ; + + using TMC2160Stepper::pwm_ofs; + using TMC2160Stepper::pwm_autograd; + using TMC2160Stepper::pwm_reg; + using TMC2160Stepper::pwm_lim; + + using TMC2160Stepper::pwm_scale_sum; + using TMC2160Stepper::pwm_scale_auto; +}; + +class TMC5160Stepper : public TMC5130Stepper { + public: + TMC5160Stepper(uint16_t pinCS, float RS = default_RS, int8_t link_index = -1); + TMC5160Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + TMC5160Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1); + + void rms_current(uint16_t mA) { TMC2160Stepper::rms_current(mA); } + void rms_current(uint16_t mA, float mult) { TMC2160Stepper::rms_current(mA, mult); } + uint16_t rms_current() { return TMC2160Stepper::rms_current(); } + void defaults(); + void push(); + + // RW: GCONF + void recalibrate(bool); + void faststandstill(bool); + void multistep_filt(bool); + bool recalibrate(); + bool faststandstill(); + bool multistep_filt(); + + // R: IOIN + bool drv_enn() { return drv_enn_cfg6(); } + bool enc_n_dco_cfg6() { return enc_n_dco(); } + + // W: SHORT_CONF + using TMC2160Stepper::SHORT_CONF; + using TMC2160Stepper::s2vs_level; + using TMC2160Stepper::s2g_level; + using TMC2160Stepper::shortfilter; + using TMC2160Stepper::shortdelay; + + // W: DRV_CONF + using TMC2160Stepper::DRV_CONF; + using TMC2160Stepper::bbmtime; + using TMC2160Stepper::bbmclks; + using TMC2160Stepper::otselect; + using TMC2160Stepper::drvstrength; + using TMC2160Stepper::filt_isense; + + // W: GLOBAL_SCALER + using TMC2160Stepper::GLOBAL_SCALER; + + // R: OFFSET_READ + using TMC2160Stepper::OFFSET_READ; + + // R+WC: ENC_STATUS + void ENC_STATUS(uint8_t); + uint8_t ENC_STATUS(); + + // W: ENC_DEVIATION + void ENC_DEVIATION(uint32_t); + uint32_t ENC_DEVIATION(); + + // R: PWM_AUTO + uint32_t PWM_AUTO(); + uint8_t pwm_ofs_auto(); + uint8_t pwm_grad_auto(); + + // RW: CHOPCONF + void diss2vs(bool); + void tpfd(uint8_t); + bool diss2vs(); + uint8_t tpfd(); + + // W: PWM_CONF + using TMC2160Stepper::PWMCONF; + using TMC2160Stepper::pwm_ofs; + using TMC2160Stepper::pwm_grad; + using TMC2160Stepper::pwm_freq; + using TMC2160Stepper::pwm_autoscale; + using TMC2160Stepper::pwm_autograd; + using TMC2160Stepper::freewheel; + using TMC2160Stepper::pwm_reg; + using TMC2160Stepper::pwm_lim; + + using TMC2160Stepper::PWM_SCALE; + using TMC2160Stepper::pwm_scale_sum; + using TMC2160Stepper::pwm_scale_auto; + + protected: + using TMC5130Stepper::I_scale_analog; + using TMC5130Stepper::internal_Rsense; + using TMC5130Stepper::enc_commutation; + using TMC5130Stepper::drv_enn_cfg6; + using TMC5130Stepper::enc_n_dco; + using TMC5130Stepper::ENCM_CTRL; + using TMC5130Stepper::vsense; + using TMC5130Stepper::rndtf; + + INIT_REGISTER(ENC_DEVIATION){.sr=0}; + + static constexpr float default_RS = 0.075; +}; + +class TMC5161Stepper : public TMC5160Stepper { + public: + TMC5161Stepper(uint16_t pinCS, float RS = default_RS, int8_t link_index = -1) : TMC5160Stepper(pinCS, RS, link_index) {} + TMC5161Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1) : + TMC5160Stepper(pinCS, pinMOSI, pinMISO, pinSCK, link_index) {} + TMC5161Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK, int8_t link_index = -1) : + TMC5160Stepper(pinCS, RS, pinMOSI, pinMISO, pinSCK, link_index) {} +}; + +class TMC2208Stepper : public TMCStepper { + public: + TMC2208Stepper(Stream * SerialPort, float RS, uint8_t addr, uint16_t mul_pin1, uint16_t mul_pin2); + TMC2208Stepper(Stream * SerialPort, float RS) : + TMC2208Stepper(SerialPort, RS, TMC2208_SLAVE_ADDR) + {} + #if SW_CAPABLE_PLATFORM + TMC2208Stepper(uint16_t SW_RX_pin, uint16_t SW_TX_pin, float RS) : + TMC2208Stepper(SW_RX_pin, SW_TX_pin, RS, TMC2208_SLAVE_ADDR) + {} + + __attribute__((deprecated("Boolean argument has been deprecated and does nothing"))) + TMC2208Stepper(uint16_t SW_RX_pin, uint16_t SW_TX_pin, float RS, bool) : + TMC2208Stepper(SW_RX_pin, SW_TX_pin, RS, TMC2208_SLAVE_ADDR) + {}; + #else + TMC2208Stepper(uint16_t, uint16_t, float) = delete; // Your platform does not currently support Software Serial + #endif + void defaults(); + void push(); + void begin(); + #if SW_CAPABLE_PLATFORM + void beginSerial(uint32_t baudrate) __attribute__((weak)); + #else + void beginSerial(uint32_t) = delete; // Your platform does not currently support Software Serial + #endif + bool isEnabled(); + + // RW: GCONF + void GCONF(uint32_t input); + void I_scale_analog(bool B); + void internal_Rsense(bool B); + void en_spreadCycle(bool B); + void shaft(bool B); + void index_otpw(bool B); + void index_step(bool B); + void pdn_disable(bool B); + void mstep_reg_select(bool B); + void multistep_filt(bool B); + uint32_t GCONF(); + bool I_scale_analog(); + bool internal_Rsense(); + bool en_spreadCycle(); + bool shaft(); + bool index_otpw(); + bool index_step(); + bool pdn_disable(); + bool mstep_reg_select(); + bool multistep_filt(); + + // R: IFCNT + uint8_t IFCNT(); + + // W: SLAVECONF + void SLAVECONF(uint16_t input); + uint16_t SLAVECONF(); + void senddelay(uint8_t B); + uint8_t senddelay(); + + // W: OTP_PROG + void OTP_PROG(uint16_t input); + + // R: OTP_READ + uint32_t OTP_READ(); + + // R: IOIN + uint32_t IOIN(); + bool enn(); + bool ms1(); + bool ms2(); + bool diag(); + bool pdn_uart(); + bool step(); + bool sel_a(); + bool dir(); + uint8_t version(); + + // RW: FACTORY_CONF + void FACTORY_CONF(uint16_t input); + uint16_t FACTORY_CONF(); + void fclktrim(uint8_t B); + void ottrim(uint8_t B); + uint8_t fclktrim(); + uint8_t ottrim(); + + // W: VACTUAL + void VACTUAL(uint32_t input); + uint32_t VACTUAL(); + + // RW: CHOPCONF + void CHOPCONF(uint32_t input); + void toff(uint8_t B); + void hstrt(uint8_t B); + void hend(uint8_t B); + void tbl(uint8_t B); + void vsense(bool B); + void mres(uint8_t B); + void intpol(bool B); + void dedge(bool B); + void diss2g(bool B); + void diss2vs(bool B); + uint32_t CHOPCONF(); + uint8_t toff(); + uint8_t hstrt(); + uint8_t hend(); + uint8_t tbl(); + bool vsense(); + uint8_t mres(); + bool intpol(); + bool dedge(); + bool diss2g(); + bool diss2vs(); + + // R: DRV_STATUS + uint32_t DRV_STATUS(); + bool otpw(); + bool ot(); + bool s2ga(); + bool s2gb(); + bool s2vsa(); + bool s2vsb(); + bool ola(); + bool olb(); + bool t120(); + bool t143(); + bool t150(); + bool t157(); + uint16_t cs_actual(); + bool stealth(); + bool stst(); + + // RW: PWMCONF + void PWMCONF(uint32_t input); + void pwm_ofs(uint8_t B); + void pwm_grad(uint8_t B); + void pwm_freq(uint8_t B); + void pwm_autoscale(bool B); + void pwm_autograd(bool B); + void freewheel(uint8_t B); + void pwm_reg(uint8_t B); + void pwm_lim(uint8_t B); + uint32_t PWMCONF(); + uint8_t pwm_ofs(); + uint8_t pwm_grad(); + uint8_t pwm_freq(); + bool pwm_autoscale(); + bool pwm_autograd(); + uint8_t freewheel(); + uint8_t pwm_reg(); + uint8_t pwm_lim(); + + // R: PWM_SCALE + uint32_t PWM_SCALE(); + uint8_t pwm_scale_sum(); + int16_t pwm_scale_auto(); + + // R: PWM_AUTO (0x72) + uint32_t PWM_AUTO(); + uint8_t pwm_ofs_auto(); + uint8_t pwm_grad_auto(); + + uint16_t bytesWritten = 0; + float Rsense = 0.11; + bool CRCerror = false; + protected: + INIT2208_REGISTER(GCONF) {{.sr=0}}; + INIT_REGISTER(SLAVECONF) {{.sr=0}}; + INIT_REGISTER(FACTORY_CONF) {{.sr=0}}; + INIT2208_REGISTER(VACTUAL) {.sr=0}; + INIT2208_REGISTER(CHOPCONF) {{.sr=0}}; + INIT2208_REGISTER(PWMCONF) {{.sr=0}}; + + struct IFCNT_t { constexpr static uint8_t address = 0x02; }; + struct OTP_PROG_t { constexpr static uint8_t address = 0x04; }; + struct OTP_READ_t { constexpr static uint8_t address = 0x05; }; + + TMC2208Stepper(Stream * SerialPort, float RS, uint8_t addr); + #if SW_CAPABLE_PLATFORM + TMC2208Stepper(uint16_t SW_RX_pin, uint16_t SW_TX_pin, float RS, uint8_t addr); + #endif + + Stream * HWSerial = nullptr; + #if SW_CAPABLE_PLATFORM + SoftwareSerial * SWSerial = nullptr; + const uint16_t RXTX_pin = 0; // Half duplex + #endif + + SSwitch *sswitch = nullptr; + + int available(); + void preWriteCommunication(); + void preReadCommunication(); + int16_t serial_read(); + uint8_t serial_write(const uint8_t data); + void postWriteCommunication(); + void postReadCommunication(); + void write(uint8_t, uint32_t); + uint32_t read(uint8_t); + const uint8_t slave_address; + uint8_t calcCRC(uint8_t datagram[], uint8_t len); + static constexpr uint8_t TMC2208_SYNC = 0x05, + TMC2208_SLAVE_ADDR = 0x00; + static constexpr uint8_t replyDelay = 2; + static constexpr uint8_t abort_window = 5; + static constexpr uint8_t max_retries = 2; + + uint64_t _sendDatagram(uint8_t [], const uint8_t, uint16_t); +}; + +class TMC2209Stepper : public TMC2208Stepper { + public: + TMC2209Stepper(Stream * SerialPort, float RS, uint8_t addr) : + TMC2208Stepper(SerialPort, RS, addr) {} + + #if SW_CAPABLE_PLATFORM + TMC2209Stepper(uint16_t SW_RX_pin, uint16_t SW_TX_pin, float RS, uint8_t addr) : + TMC2208Stepper(SW_RX_pin, SW_TX_pin, RS, addr) {} + #else + TMC2209Stepper(uint16_t, uint16_t, float, uint8_t) = delete; // Your platform does not currently support Software Serial + #endif + void push(); + + // R: IOIN + uint32_t IOIN(); + bool enn(); + bool ms1(); + bool ms2(); + bool diag(); + bool pdn_uart(); + bool step(); + bool spread_en(); + bool dir(); + uint8_t version(); + + // W: TCOOLTHRS + uint32_t TCOOLTHRS(); + void TCOOLTHRS(uint32_t input); + + // W: SGTHRS + void SGTHRS(uint8_t B); + uint8_t SGTHRS(); + + // R: SG_RESULT + uint16_t SG_RESULT(); + + // W: COOLCONF + void COOLCONF(uint16_t B); + uint16_t COOLCONF(); + void semin(uint8_t B); + void seup(uint8_t B); + void semax(uint8_t B); + void sedn(uint8_t B); + void seimin(bool B); + uint8_t semin(); + uint8_t seup(); + uint8_t semax(); + uint8_t sedn(); + bool seimin(); + + protected: + INIT_REGISTER(TCOOLTHRS){.sr=0}; + TMC2209_n::SGTHRS_t SGTHRS_register{.sr=0}; + TMC2209_n::COOLCONF_t COOLCONF_register{{.sr=0}}; +}; + +class TMC2224Stepper : public TMC2208Stepper { + public: + uint32_t IOIN(); + bool enn(); + bool ms1(); + bool ms2(); + bool pdn_uart(); + bool spread(); + bool step(); + bool sel_a(); + bool dir(); + uint8_t version(); +}; + +class TMC2660Stepper { + public: + TMC2660Stepper(uint16_t pinCS, float RS = default_RS); + TMC2660Stepper(uint16_t pinCS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK); + TMC2660Stepper(uint16_t pinCS, float RS, uint16_t pinMOSI, uint16_t pinMISO, uint16_t pinSCK); + void write(uint8_t addressByte, uint32_t config); + uint32_t read(); + void switchCSpin(bool state); + void begin(); + bool isEnabled(); + uint8_t test_connection(); + uint16_t cs2rms(uint8_t CS); + uint16_t rms_current(); + void rms_current(uint16_t mA); + //uint16_t getMilliamps() {return val_mA;} + void push(); + uint8_t savedToff() { return _savedToff; } + + // Helper functions + void microsteps(uint16_t ms); + uint16_t microsteps(); + void blank_time(uint8_t value); + uint8_t blank_time(); + void hysteresis_end(int8_t value); + int8_t hysteresis_end(); + void hysteresis_start(uint8_t value); + uint8_t hysteresis_start(); + + // W: DRVCONF + void DRVCONF(uint32_t); + void tst(bool); + void slph(uint8_t); + void slpl(uint8_t); + void diss2g(bool); + void ts2g(uint8_t); + void sdoff(bool); + void vsense(bool); + void rdsel(uint8_t); + uint32_t DRVCONF(); + bool tst(); + uint8_t slph(); + uint8_t slpl(); + bool diss2g(); + uint8_t ts2g(); + bool sdoff(); + bool vsense(); + uint8_t rdsel(); + + // W: DRVCTRL + void DRVCTRL(uint32_t); + void pha(bool B); + void ca(uint8_t B); + void phb(bool B); + void cb(uint8_t B); + bool pha(); + uint8_t ca(); + bool phb(); + uint8_t cb(); + void intpol(bool); + void dedge(bool); + void mres(uint8_t); + uint32_t DRVCTRL(); + bool intpol(); + bool dedge(); + uint8_t mres(); + + // W: CHOPCONF + void CHOPCONF(uint32_t); + void tbl(uint8_t); + void chm(bool); + void rndtf(bool); + void hdec(uint8_t); + void hend(uint8_t); + void hstrt(uint8_t); + void toff(uint8_t); + uint32_t CHOPCONF(); + uint8_t tbl(); + bool chm(); + bool rndtf(); + uint8_t hdec(); + uint8_t hend(); + uint8_t hstrt(); + uint8_t toff(); + + // R: DRVSTATUS + uint32_t DRV_STATUS() { return DRVSTATUS(); } + uint32_t DRVSTATUS(); + uint16_t mstep(); + uint8_t se(); + bool stst(); + bool olb(); + bool ola(); + bool s2gb(); + bool s2ga(); + bool otpw(); + bool ot(); + bool sg(); + uint16_t sg_result(); + + // W: SGCSCONF + uint32_t SGCSCONF(); + void sfilt(bool); + void sgt(uint8_t); + void cs(uint8_t); + void SGCSCONF(uint32_t); + bool sfilt(); + uint8_t sgt(); + uint8_t cs(); + + // W: SMARTEN + void SMARTEN(uint32_t); + void seimin(bool B); + void sedn(uint8_t B); + void semax(uint8_t B); + void seup(uint8_t B); + void semin(uint8_t B); + uint32_t SMARTEN(); + bool seimin(); + uint8_t sedn(); + uint8_t semax(); + uint8_t seup(); + uint8_t semin(); + /* + // Alias + SET_ALIAS(void, polarity_A, bool, pha); + SET_ALIAS(void, current_A, uint8_t, ca); + SET_ALIAS(void, polarity_B, bool, phb); + SET_ALIAS(void, current_b, uint8_t, cb); + SET_ALIAS(void, interpolate, bool, intpol); + SET_ALIAS(void, double_edge_step, bool, dedge); + SET_ALIAS(void, microsteps, uint8_t, mres); + SET_ALIAS(void, blank_time, uint8_t, tbl); + SET_ALIAS(void, chopper_mode, bool, chm); + SET_ALIAS(void, random_off_time, bool, rndtf); + SET_ALIAS(void, hysteresis_decrement, uint8_t, hdec); + SET_ALIAS(void, hysteresis_low, uint8_t, hend); + SET_ALIAS(void, hysteresis_start, uint8_t, hstrt); + SET_ALIAS(void, off_time, uint8_t, toff); + */ + + uint8_t status_response; + + private: + INIT_REGISTER(DRVCTRL_1){{.sr=0}}; + INIT_REGISTER(DRVCTRL_0){{.sr=0}}; + INIT2660_REGISTER(CHOPCONF){{.sr=0}}; + INIT_REGISTER(SMARTEN){{.sr=0}}; + INIT_REGISTER(SGCSCONF){{.sr=0}}; + INIT_REGISTER(DRVCONF){{.sr=0}}; + INIT_REGISTER(READ_RDSEL00){{.sr=0}}; + INIT_REGISTER(READ_RDSEL01){{.sr=0}}; + INIT_REGISTER(READ_RDSEL10){{.sr=0}}; + + const uint16_t _pinCS; + const float Rsense; + static constexpr float default_RS = 0.1; + float holdMultiplier = 0.5; + uint32_t spi_speed = 16000000/8; // Default 2MHz + uint8_t _savedToff = 0; + SW_SPIClass * TMC_SW_SPI = nullptr; +}; diff --git a/X86TestSupport/TMC/TMCStepper_UTILITY.h b/X86TestSupport/TMC/TMCStepper_UTILITY.h new file mode 100644 index 00000000..a64e944f --- /dev/null +++ b/X86TestSupport/TMC/TMCStepper_UTILITY.h @@ -0,0 +1,33 @@ +#ifndef TMCStepper_UTILITY_h +#define TMCStepper_UTILITY_h + +void print_HEX(uint32_t data) { + for(uint8_t B=24; B>=4; B-=8){ + Serial.print((data>>(B+4))&0xF, HEX); + Serial.print((data>>B)&0xF, HEX); + Serial.print(":"); + } + Serial.print((data>>4)&0xF, HEX); + Serial.print(data&0xF, HEX); +} + +void print_BIN(uint32_t data) { + int b = 31; + for(; b>=24; b--){ + Serial.print((data>>b)&0b1); + } + Serial.print("."); + for(; b>=16; b--){ + Serial.print((data>>b)&0b1); + } + Serial.print("."); + for(; b>=8; b--){ + Serial.print((data>>b)&0b1); + } + Serial.print("."); + for(; b>=0; b--){ + Serial.print((data>>b)&0b1); + } +} + +#endif diff --git a/X86TestSupport/TMCStepper.h b/X86TestSupport/TMCStepper.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/TMCStepper.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/WString.h b/X86TestSupport/WString.h index a25e508d..88fe018f 100644 --- a/X86TestSupport/WString.h +++ b/X86TestSupport/WString.h @@ -222,18 +222,35 @@ public: String substring(int index) { return String(backbuf.substr(index)); } // modification - // void replace(char find, char replace); + void replace(char find, char replace) { + std::string s2 = backbuf; + for (auto& it : s2) { + if (it == find) { + it = replace; + } + } + backbuf = s2; + } // void replace(const String& find, const String& replace); // void remove(unsigned int index); // void remove(unsigned int index, unsigned int count); - // void toLowerCase(void); - // void toUpperCase(void); // void trim(void); // parsing/conversion long toInt() const { return atoi(backbuf.c_str()); } float toFloat() const { return std::stof(backbuf.c_str()); } double toDouble() const { return std::stod(backbuf.c_str()); } + + inline void toLowerCase() { + for (auto& it : backbuf) { + it = std::tolower(it); + } + } + inline void toUpperCase() { + for (auto& it : backbuf) { + it = std::toupper(it); + } + } }; class StringAppender : public String { @@ -250,5 +267,5 @@ public: StringAppender(double num) : String(num) {} }; -int strcasecmp(const char* lhs, const char* rhs); -int strncasecmp(const char* lhs, const char* rhs, size_t count); +int strcasecmp(const char* lhs, const char* rhs); +int strncasecmp(const char* lhs, const char* rhs, size_t count); diff --git a/X86TestSupport/driver/dac.h b/X86TestSupport/driver/dac.h new file mode 100644 index 00000000..54299fa8 --- /dev/null +++ b/X86TestSupport/driver/dac.h @@ -0,0 +1,5 @@ +#pragma once + +#include + +void dacWrite(uint8_t pin, uint8_t value); diff --git a/X86TestSupport/driver/ledc.h b/X86TestSupport/driver/ledc.h new file mode 100644 index 00000000..75c1ef15 --- /dev/null +++ b/X86TestSupport/driver/ledc.h @@ -0,0 +1,6 @@ +#pragma once + +#include + +void pinMatrixOutAttach(uint8_t pin, uint8_t function, bool invertOut, bool invertEnable); +void pinMatrixOutDetach(uint8_t pin, bool invertOut, bool invertEnable); diff --git a/X86TestSupport/driver/rmt.h b/X86TestSupport/driver/rmt.h new file mode 100644 index 00000000..6c010628 --- /dev/null +++ b/X86TestSupport/driver/rmt.h @@ -0,0 +1,353 @@ +// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at + +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#pragma once + +typedef struct rmt_item32_s { + union { + struct { + uint32_t duration0 : 15; + uint32_t level0 : 1; + uint32_t duration1 : 15; + uint32_t level1 : 1; + }; + uint32_t val; + }; +} rmt_item32_t; + +typedef enum { + RMT_CHANNEL_0 = 0, /*!< RMT Channel 0 */ + RMT_CHANNEL_1, /*!< RMT Channel 1 */ + RMT_CHANNEL_2, /*!< RMT Channel 2 */ + RMT_CHANNEL_3, /*!< RMT Channel 3 */ + RMT_CHANNEL_4, /*!< RMT Channel 4 */ + RMT_CHANNEL_5, /*!< RMT Channel 5 */ + RMT_CHANNEL_6, /*!< RMT Channel 6 */ + RMT_CHANNEL_7, /*!< RMT Channel 7 */ + RMT_CHANNEL_MAX +} rmt_channel_t; + +typedef enum { + RMT_MODE_TX = 0, /*!< RMT TX mode */ + RMT_MODE_RX, /*!< RMT RX mode */ + RMT_MODE_MAX +} rmt_mode_t; + +typedef enum { + RMT_CARRIER_LEVEL_LOW = 0, /*!< RMT carrier wave is modulated for low Level output */ + RMT_CARRIER_LEVEL_HIGH, /*!< RMT carrier wave is modulated for high Level output */ + RMT_CARRIER_LEVEL_MAX +} rmt_carrier_level_t; + +typedef enum { + RMT_BASECLK_REF = 0, /*!< RMT source clock system reference tick, 1MHz by default (not supported in this version) */ + RMT_BASECLK_APB, /*!< RMT source clock is APB CLK, 80Mhz by default */ + RMT_BASECLK_MAX, +} rmt_source_clk_t; + +typedef enum { + RMT_IDLE_LEVEL_LOW = 0, /*!< RMT TX idle level: low Level */ + RMT_IDLE_LEVEL_HIGH, /*!< RMT TX idle level: high Level */ + RMT_IDLE_LEVEL_MAX, +} rmt_idle_level_t; + +/** + * @brief Data struct of RMT TX configure parameters + */ +typedef struct { + bool loop_en; /*!< Enable sending RMT items in a loop */ + uint32_t carrier_freq_hz; /*!< RMT carrier frequency */ + uint8_t carrier_duty_percent; /*!< RMT carrier duty (%) */ + rmt_carrier_level_t carrier_level; /*!< Level of the RMT output, when the carrier is applied */ + bool carrier_en; /*!< RMT carrier enable */ + rmt_idle_level_t idle_level; /*!< RMT idle level */ + bool idle_output_en; /*!< RMT idle level output enable */ +} rmt_tx_config_t; + +/** + * @brief Data struct of RMT RX configure parameters + */ +typedef struct { + bool filter_en; /*!< RMT receiver filter enable */ + uint8_t filter_ticks_thresh; /*!< RMT filter tick number */ + uint16_t idle_threshold; /*!< RMT RX idle threshold */ +} rmt_rx_config_t; + +typedef struct { + rmt_mode_t rmt_mode; /*!< RMT mode: transmitter or receiver */ + rmt_channel_t channel; /*!< RMT channel */ + uint8_t clk_div; /*!< RMT channel counter divider */ + int gpio_num; /*!< RMT GPIO number */ + uint8_t mem_block_num; /*!< RMT memory block number */ + union { + rmt_tx_config_t tx_config; /*!< RMT TX parameter */ + rmt_rx_config_t rx_config; /*!< RMT RX parameter */ + }; +} rmt_config_t; + +/** + * @brief Set RMT source clock + * + * RMT module has two clock sources: + * 1. APB clock which is 80Mhz + * 2. REF tick clock, which would be 1Mhz (not supported in this version). + * + * @param channel RMT channel (0-7) + * @param base_clk To choose source clock for RMT module. + * + * @return + * - ESP_ERR_INVALID_ARG Parameter error + * - ESP_OK Success + */ +esp_err_t rmt_set_source_clk(rmt_channel_t channel, rmt_source_clk_t base_clk); + +/** + * @brief Configure RMT parameters + * + * @param rmt_param RMT parameter struct + * + * @return + * - ESP_ERR_INVALID_ARG Parameter error + * - ESP_OK Success + */ +esp_err_t rmt_config(const rmt_config_t* rmt_param); + +/** + * @brief Fill memory data of channel with given RMT items. + * + * @param channel RMT channel (0 - 7) + * @param item Pointer of items. + * @param item_num RMT sending items number. + * @param mem_offset Index offset of memory. + * + * @return + * - ESP_ERR_INVALID_ARG Parameter error + * - ESP_OK Success + */ +esp_err_t rmt_fill_tx_items(rmt_channel_t channel, const rmt_item32_t* item, uint16_t item_num, uint16_t mem_offset); + +typedef volatile struct rmt_dev_s { + uint32_t data_ch[8]; /*The R/W ram address for channel0-7 by apb fifo access. + Note that in some circumstances, data read from the FIFO may get lost. As RMT memory area accesses using the RMTMEM method do not have this issue + and provide all the functionality that the FIFO register has, it is encouraged to use that instead.*/ + struct { + union { + struct { + uint32_t div_cnt : 8; /*This register is used to configure the frequency divider's factor in channel0-7.*/ + uint32_t idle_thres : 16; /*In receive mode when no edge is detected on the input signal for longer than reg_idle_thres_ch0 then the receive process is done.*/ + uint32_t mem_size : 4; /*This register is used to configure the the amount of memory blocks allocated to channel0-7.*/ + uint32_t carrier_en : 1; /*This is the carrier modulation enable control bit for channel0-7.*/ + uint32_t carrier_out_lv : 1; /*This bit is used to configure the way carrier wave is modulated for channel0-7.1'b1:transmit on low output level 1'b0:transmit on high output level.*/ + uint32_t mem_pd : 1; /*This bit is used to reduce power consumed by memory. 1:memory is in low power state.*/ + uint32_t clk_en : 1; /*This bit is used to control clock.when software configure RMT internal registers it controls the register clock.*/ + }; + uint32_t val; + } conf0; + union { + struct { + uint32_t tx_start : 1; /*Set this bit to start sending data for channel0-7.*/ + uint32_t rx_en : 1; /*Set this bit to enable receiving data for channel0-7.*/ + uint32_t mem_wr_rst : 1; /*Set this bit to reset write ram address for channel0-7 by receiver access.*/ + uint32_t mem_rd_rst : 1; /*Set this bit to reset read ram address for channel0-7 by transmitter access.*/ + uint32_t apb_mem_rst : 1; /*Set this bit to reset W/R ram address for channel0-7 by apb fifo access (using fifo is discouraged, please see the note above at data_ch[] item)*/ + uint32_t mem_owner : 1; /*This is the mark of channel0-7's ram usage right.1'b1:receiver uses the ram 0:transmitter uses the ram*/ + uint32_t tx_conti_mode : 1; /*Set this bit to continue sending from the first data to the last data in channel0-7 again and again.*/ + uint32_t rx_filter_en : 1; /*This is the receive filter enable bit for channel0-7.*/ + uint32_t rx_filter_thres : 8; /*in receive mode channel0-7 ignore input pulse when the pulse width is smaller then this value.*/ + uint32_t ref_cnt_rst : 1; /*This bit is used to reset divider in channel0-7.*/ + uint32_t ref_always_on : 1; /*This bit is used to select base clock. 1'b1:clk_apb 1'b0:clk_ref*/ + uint32_t idle_out_lv : 1; /*This bit configures the output signal's level for channel0-7 in IDLE state.*/ + uint32_t idle_out_en : 1; /*This is the output enable control bit for channel0-7 in IDLE state.*/ + uint32_t reserved20 : 12; + }; + uint32_t val; + } conf1; + } conf_ch[8]; + uint32_t status_ch[8]; /*The status for channel0-7*/ + uint32_t apb_mem_addr_ch[8]; /*The ram relative address in channel0-7 by apb fifo access (using fifo is discouraged, please see the note above at data_ch[] item)*/ + union { + struct { + uint32_t ch0_tx_end : 1; /*The interrupt raw bit for channel 0 turns to high level when the transmit process is done.*/ + uint32_t ch0_rx_end : 1; /*The interrupt raw bit for channel 0 turns to high level when the receive process is done.*/ + uint32_t ch0_err : 1; /*The interrupt raw bit for channel 0 turns to high level when channel 0 detects some errors.*/ + uint32_t ch1_tx_end : 1; /*The interrupt raw bit for channel 1 turns to high level when the transmit process is done.*/ + uint32_t ch1_rx_end : 1; /*The interrupt raw bit for channel 1 turns to high level when the receive process is done.*/ + uint32_t ch1_err : 1; /*The interrupt raw bit for channel 1 turns to high level when channel 1 detects some errors.*/ + uint32_t ch2_tx_end : 1; /*The interrupt raw bit for channel 2 turns to high level when the transmit process is done.*/ + uint32_t ch2_rx_end : 1; /*The interrupt raw bit for channel 2 turns to high level when the receive process is done.*/ + uint32_t ch2_err : 1; /*The interrupt raw bit for channel 2 turns to high level when channel 2 detects some errors.*/ + uint32_t ch3_tx_end : 1; /*The interrupt raw bit for channel 3 turns to high level when the transmit process is done.*/ + uint32_t ch3_rx_end : 1; /*The interrupt raw bit for channel 3 turns to high level when the receive process is done.*/ + uint32_t ch3_err : 1; /*The interrupt raw bit for channel 3 turns to high level when channel 3 detects some errors.*/ + uint32_t ch4_tx_end : 1; /*The interrupt raw bit for channel 4 turns to high level when the transmit process is done.*/ + uint32_t ch4_rx_end : 1; /*The interrupt raw bit for channel 4 turns to high level when the receive process is done.*/ + uint32_t ch4_err : 1; /*The interrupt raw bit for channel 4 turns to high level when channel 4 detects some errors.*/ + uint32_t ch5_tx_end : 1; /*The interrupt raw bit for channel 5 turns to high level when the transmit process is done.*/ + uint32_t ch5_rx_end : 1; /*The interrupt raw bit for channel 5 turns to high level when the receive process is done.*/ + uint32_t ch5_err : 1; /*The interrupt raw bit for channel 5 turns to high level when channel 5 detects some errors.*/ + uint32_t ch6_tx_end : 1; /*The interrupt raw bit for channel 6 turns to high level when the transmit process is done.*/ + uint32_t ch6_rx_end : 1; /*The interrupt raw bit for channel 6 turns to high level when the receive process is done.*/ + uint32_t ch6_err : 1; /*The interrupt raw bit for channel 6 turns to high level when channel 6 detects some errors.*/ + uint32_t ch7_tx_end : 1; /*The interrupt raw bit for channel 7 turns to high level when the transmit process is done.*/ + uint32_t ch7_rx_end : 1; /*The interrupt raw bit for channel 7 turns to high level when the receive process is done.*/ + uint32_t ch7_err : 1; /*The interrupt raw bit for channel 7 turns to high level when channel 7 detects some errors.*/ + uint32_t ch0_tx_thr_event : 1; /*The interrupt raw bit for channel 0 turns to high level when transmitter in channel0 have send data more than reg_rmt_tx_lim_ch0 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch1_tx_thr_event : 1; /*The interrupt raw bit for channel 1 turns to high level when transmitter in channel1 have send data more than reg_rmt_tx_lim_ch1 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch2_tx_thr_event : 1; /*The interrupt raw bit for channel 2 turns to high level when transmitter in channel2 have send data more than reg_rmt_tx_lim_ch2 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch3_tx_thr_event : 1; /*The interrupt raw bit for channel 3 turns to high level when transmitter in channel3 have send data more than reg_rmt_tx_lim_ch3 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch4_tx_thr_event : 1; /*The interrupt raw bit for channel 4 turns to high level when transmitter in channel4 have send data more than reg_rmt_tx_lim_ch4 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch5_tx_thr_event : 1; /*The interrupt raw bit for channel 5 turns to high level when transmitter in channel5 have send data more than reg_rmt_tx_lim_ch5 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch6_tx_thr_event : 1; /*The interrupt raw bit for channel 6 turns to high level when transmitter in channel6 have send data more than reg_rmt_tx_lim_ch6 after detecting this interrupt software can updata the old data with new data.*/ + uint32_t ch7_tx_thr_event : 1; /*The interrupt raw bit for channel 7 turns to high level when transmitter in channel7 have send data more than reg_rmt_tx_lim_ch7 after detecting this interrupt software can updata the old data with new data.*/ + }; + uint32_t val; + } int_raw; + union { + struct { + uint32_t ch0_tx_end : 1; /*The interrupt state bit for channel 0's mt_ch0_tx_end_int_raw when mt_ch0_tx_end_int_ena is set to 0.*/ + uint32_t ch0_rx_end : 1; /*The interrupt state bit for channel 0's rmt_ch0_rx_end_int_raw when rmt_ch0_rx_end_int_ena is set to 0.*/ + uint32_t ch0_err : 1; /*The interrupt state bit for channel 0's rmt_ch0_err_int_raw when rmt_ch0_err_int_ena is set to 0.*/ + uint32_t ch1_tx_end : 1; /*The interrupt state bit for channel 1's mt_ch1_tx_end_int_raw when mt_ch1_tx_end_int_ena is set to 1.*/ + uint32_t ch1_rx_end : 1; /*The interrupt state bit for channel 1's rmt_ch1_rx_end_int_raw when rmt_ch1_rx_end_int_ena is set to 1.*/ + uint32_t ch1_err : 1; /*The interrupt state bit for channel 1's rmt_ch1_err_int_raw when rmt_ch1_err_int_ena is set to 1.*/ + uint32_t ch2_tx_end : 1; /*The interrupt state bit for channel 2's mt_ch2_tx_end_int_raw when mt_ch2_tx_end_int_ena is set to 1.*/ + uint32_t ch2_rx_end : 1; /*The interrupt state bit for channel 2's rmt_ch2_rx_end_int_raw when rmt_ch2_rx_end_int_ena is set to 1.*/ + uint32_t ch2_err : 1; /*The interrupt state bit for channel 2's rmt_ch2_err_int_raw when rmt_ch2_err_int_ena is set to 1.*/ + uint32_t ch3_tx_end : 1; /*The interrupt state bit for channel 3's mt_ch3_tx_end_int_raw when mt_ch3_tx_end_int_ena is set to 1.*/ + uint32_t ch3_rx_end : 1; /*The interrupt state bit for channel 3's rmt_ch3_rx_end_int_raw when rmt_ch3_rx_end_int_ena is set to 1.*/ + uint32_t ch3_err : 1; /*The interrupt state bit for channel 3's rmt_ch3_err_int_raw when rmt_ch3_err_int_ena is set to 1.*/ + uint32_t ch4_tx_end : 1; /*The interrupt state bit for channel 4's mt_ch4_tx_end_int_raw when mt_ch4_tx_end_int_ena is set to 1.*/ + uint32_t ch4_rx_end : 1; /*The interrupt state bit for channel 4's rmt_ch4_rx_end_int_raw when rmt_ch4_rx_end_int_ena is set to 1.*/ + uint32_t ch4_err : 1; /*The interrupt state bit for channel 4's rmt_ch4_err_int_raw when rmt_ch4_err_int_ena is set to 1.*/ + uint32_t ch5_tx_end : 1; /*The interrupt state bit for channel 5's mt_ch5_tx_end_int_raw when mt_ch5_tx_end_int_ena is set to 1.*/ + uint32_t ch5_rx_end : 1; /*The interrupt state bit for channel 5's rmt_ch5_rx_end_int_raw when rmt_ch5_rx_end_int_ena is set to 1.*/ + uint32_t ch5_err : 1; /*The interrupt state bit for channel 5's rmt_ch5_err_int_raw when rmt_ch5_err_int_ena is set to 1.*/ + uint32_t ch6_tx_end : 1; /*The interrupt state bit for channel 6's mt_ch6_tx_end_int_raw when mt_ch6_tx_end_int_ena is set to 1.*/ + uint32_t ch6_rx_end : 1; /*The interrupt state bit for channel 6's rmt_ch6_rx_end_int_raw when rmt_ch6_rx_end_int_ena is set to 1.*/ + uint32_t ch6_err : 1; /*The interrupt state bit for channel 6's rmt_ch6_err_int_raw when rmt_ch6_err_int_ena is set to 1.*/ + uint32_t ch7_tx_end : 1; /*The interrupt state bit for channel 7's mt_ch7_tx_end_int_raw when mt_ch7_tx_end_int_ena is set to 1.*/ + uint32_t ch7_rx_end : 1; /*The interrupt state bit for channel 7's rmt_ch7_rx_end_int_raw when rmt_ch7_rx_end_int_ena is set to 1.*/ + uint32_t ch7_err : 1; /*The interrupt state bit for channel 7's rmt_ch7_err_int_raw when rmt_ch7_err_int_ena is set to 1.*/ + uint32_t ch0_tx_thr_event : 1; /*The interrupt state bit for channel 0's rmt_ch0_tx_thr_event_int_raw when mt_ch0_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch1_tx_thr_event : 1; /*The interrupt state bit for channel 1's rmt_ch1_tx_thr_event_int_raw when mt_ch1_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch2_tx_thr_event : 1; /*The interrupt state bit for channel 2's rmt_ch2_tx_thr_event_int_raw when mt_ch2_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch3_tx_thr_event : 1; /*The interrupt state bit for channel 3's rmt_ch3_tx_thr_event_int_raw when mt_ch3_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch4_tx_thr_event : 1; /*The interrupt state bit for channel 4's rmt_ch4_tx_thr_event_int_raw when mt_ch4_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch5_tx_thr_event : 1; /*The interrupt state bit for channel 5's rmt_ch5_tx_thr_event_int_raw when mt_ch5_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch6_tx_thr_event : 1; /*The interrupt state bit for channel 6's rmt_ch6_tx_thr_event_int_raw when mt_ch6_tx_thr_event_int_ena is set to 1.*/ + uint32_t ch7_tx_thr_event : 1; /*The interrupt state bit for channel 7's rmt_ch7_tx_thr_event_int_raw when mt_ch7_tx_thr_event_int_ena is set to 1.*/ + }; + uint32_t val; + } int_st; + union { + struct { + uint32_t ch0_tx_end : 1; /*Set this bit to enable rmt_ch0_tx_end_int_st.*/ + uint32_t ch0_rx_end : 1; /*Set this bit to enable rmt_ch0_rx_end_int_st.*/ + uint32_t ch0_err : 1; /*Set this bit to enable rmt_ch0_err_int_st.*/ + uint32_t ch1_tx_end : 1; /*Set this bit to enable rmt_ch1_tx_end_int_st.*/ + uint32_t ch1_rx_end : 1; /*Set this bit to enable rmt_ch1_rx_end_int_st.*/ + uint32_t ch1_err : 1; /*Set this bit to enable rmt_ch1_err_int_st.*/ + uint32_t ch2_tx_end : 1; /*Set this bit to enable rmt_ch2_tx_end_int_st.*/ + uint32_t ch2_rx_end : 1; /*Set this bit to enable rmt_ch2_rx_end_int_st.*/ + uint32_t ch2_err : 1; /*Set this bit to enable rmt_ch2_err_int_st.*/ + uint32_t ch3_tx_end : 1; /*Set this bit to enable rmt_ch3_tx_end_int_st.*/ + uint32_t ch3_rx_end : 1; /*Set this bit to enable rmt_ch3_rx_end_int_st.*/ + uint32_t ch3_err : 1; /*Set this bit to enable rmt_ch3_err_int_st.*/ + uint32_t ch4_tx_end : 1; /*Set this bit to enable rmt_ch4_tx_end_int_st.*/ + uint32_t ch4_rx_end : 1; /*Set this bit to enable rmt_ch4_rx_end_int_st.*/ + uint32_t ch4_err : 1; /*Set this bit to enable rmt_ch4_err_int_st.*/ + uint32_t ch5_tx_end : 1; /*Set this bit to enable rmt_ch5_tx_end_int_st.*/ + uint32_t ch5_rx_end : 1; /*Set this bit to enable rmt_ch5_rx_end_int_st.*/ + uint32_t ch5_err : 1; /*Set this bit to enable rmt_ch5_err_int_st.*/ + uint32_t ch6_tx_end : 1; /*Set this bit to enable rmt_ch6_tx_end_int_st.*/ + uint32_t ch6_rx_end : 1; /*Set this bit to enable rmt_ch6_rx_end_int_st.*/ + uint32_t ch6_err : 1; /*Set this bit to enable rmt_ch6_err_int_st.*/ + uint32_t ch7_tx_end : 1; /*Set this bit to enable rmt_ch7_tx_end_int_st.*/ + uint32_t ch7_rx_end : 1; /*Set this bit to enable rmt_ch7_rx_end_int_st.*/ + uint32_t ch7_err : 1; /*Set this bit to enable rmt_ch7_err_int_st.*/ + uint32_t ch0_tx_thr_event : 1; /*Set this bit to enable rmt_ch0_tx_thr_event_int_st.*/ + uint32_t ch1_tx_thr_event : 1; /*Set this bit to enable rmt_ch1_tx_thr_event_int_st.*/ + uint32_t ch2_tx_thr_event : 1; /*Set this bit to enable rmt_ch2_tx_thr_event_int_st.*/ + uint32_t ch3_tx_thr_event : 1; /*Set this bit to enable rmt_ch3_tx_thr_event_int_st.*/ + uint32_t ch4_tx_thr_event : 1; /*Set this bit to enable rmt_ch4_tx_thr_event_int_st.*/ + uint32_t ch5_tx_thr_event : 1; /*Set this bit to enable rmt_ch5_tx_thr_event_int_st.*/ + uint32_t ch6_tx_thr_event : 1; /*Set this bit to enable rmt_ch6_tx_thr_event_int_st.*/ + uint32_t ch7_tx_thr_event : 1; /*Set this bit to enable rmt_ch7_tx_thr_event_int_st.*/ + }; + uint32_t val; + } int_ena; + union { + struct { + uint32_t ch0_tx_end : 1; /*Set this bit to clear the rmt_ch0_rx_end_int_raw..*/ + uint32_t ch0_rx_end : 1; /*Set this bit to clear the rmt_ch0_tx_end_int_raw.*/ + uint32_t ch0_err : 1; /*Set this bit to clear the rmt_ch0_err_int_raw.*/ + uint32_t ch1_tx_end : 1; /*Set this bit to clear the rmt_ch1_rx_end_int_raw..*/ + uint32_t ch1_rx_end : 1; /*Set this bit to clear the rmt_ch1_tx_end_int_raw.*/ + uint32_t ch1_err : 1; /*Set this bit to clear the rmt_ch1_err_int_raw.*/ + uint32_t ch2_tx_end : 1; /*Set this bit to clear the rmt_ch2_rx_end_int_raw..*/ + uint32_t ch2_rx_end : 1; /*Set this bit to clear the rmt_ch2_tx_end_int_raw.*/ + uint32_t ch2_err : 1; /*Set this bit to clear the rmt_ch2_err_int_raw.*/ + uint32_t ch3_tx_end : 1; /*Set this bit to clear the rmt_ch3_rx_end_int_raw..*/ + uint32_t ch3_rx_end : 1; /*Set this bit to clear the rmt_ch3_tx_end_int_raw.*/ + uint32_t ch3_err : 1; /*Set this bit to clear the rmt_ch3_err_int_raw.*/ + uint32_t ch4_tx_end : 1; /*Set this bit to clear the rmt_ch4_rx_end_int_raw..*/ + uint32_t ch4_rx_end : 1; /*Set this bit to clear the rmt_ch4_tx_end_int_raw.*/ + uint32_t ch4_err : 1; /*Set this bit to clear the rmt_ch4_err_int_raw.*/ + uint32_t ch5_tx_end : 1; /*Set this bit to clear the rmt_ch5_rx_end_int_raw..*/ + uint32_t ch5_rx_end : 1; /*Set this bit to clear the rmt_ch5_tx_end_int_raw.*/ + uint32_t ch5_err : 1; /*Set this bit to clear the rmt_ch5_err_int_raw.*/ + uint32_t ch6_tx_end : 1; /*Set this bit to clear the rmt_ch6_rx_end_int_raw..*/ + uint32_t ch6_rx_end : 1; /*Set this bit to clear the rmt_ch6_tx_end_int_raw.*/ + uint32_t ch6_err : 1; /*Set this bit to clear the rmt_ch6_err_int_raw.*/ + uint32_t ch7_tx_end : 1; /*Set this bit to clear the rmt_ch7_rx_end_int_raw..*/ + uint32_t ch7_rx_end : 1; /*Set this bit to clear the rmt_ch7_tx_end_int_raw.*/ + uint32_t ch7_err : 1; /*Set this bit to clear the rmt_ch7_err_int_raw.*/ + uint32_t ch0_tx_thr_event : 1; /*Set this bit to clear the rmt_ch0_tx_thr_event_int_raw interrupt.*/ + uint32_t ch1_tx_thr_event : 1; /*Set this bit to clear the rmt_ch1_tx_thr_event_int_raw interrupt.*/ + uint32_t ch2_tx_thr_event : 1; /*Set this bit to clear the rmt_ch2_tx_thr_event_int_raw interrupt.*/ + uint32_t ch3_tx_thr_event : 1; /*Set this bit to clear the rmt_ch3_tx_thr_event_int_raw interrupt.*/ + uint32_t ch4_tx_thr_event : 1; /*Set this bit to clear the rmt_ch4_tx_thr_event_int_raw interrupt.*/ + uint32_t ch5_tx_thr_event : 1; /*Set this bit to clear the rmt_ch5_tx_thr_event_int_raw interrupt.*/ + uint32_t ch6_tx_thr_event : 1; /*Set this bit to clear the rmt_ch6_tx_thr_event_int_raw interrupt.*/ + uint32_t ch7_tx_thr_event : 1; /*Set this bit to clear the rmt_ch7_tx_thr_event_int_raw interrupt.*/ + }; + uint32_t val; + } int_clr; + union { + struct { + uint32_t low : 16; /*This register is used to configure carrier wave's low level value for channel0-7.*/ + uint32_t high : 16; /*This register is used to configure carrier wave's high level value for channel0-7.*/ + }; + uint32_t val; + } carrier_duty_ch[8]; + union { + struct { + uint32_t limit : 9; /*When channel0-7 sends more than reg_rmt_tx_lim_ch0 data then channel0-7 produce the relative interrupt.*/ + uint32_t reserved9 : 23; + }; + uint32_t val; + } tx_lim_ch[8]; + union { + struct { + uint32_t fifo_mask : 1; /*Set this bit to enable RMTMEM and disable apb fifo access (using fifo is discouraged, please see the note above at data_ch[] item)*/ + uint32_t mem_tx_wrap_en : 1; /*when data need to be send is more than channel's mem can store then set this bit to enable reuse of mem this bit is used together with reg_rmt_tx_lim_chn.*/ + uint32_t reserved2 : 30; + }; + uint32_t val; + } apb_conf; + uint32_t reserved_f4; + uint32_t reserved_f8; + uint32_t date; /*This is the version register.*/ +} rmt_dev_t; +extern rmt_dev_t RMT; diff --git a/X86TestSupport/driver/uart.h b/X86TestSupport/driver/uart.h index 379a2f67..9b719268 100644 --- a/X86TestSupport/driver/uart.h +++ b/X86TestSupport/driver/uart.h @@ -1,5 +1,10 @@ #pragma once +#include + +#include "freertos/FreeRTOS.h" +#include "esp_err.h" + /** * @brief UART mode selection */ @@ -50,3 +55,35 @@ typedef enum { UART_PARITY_EVEN = 0x2, /*!< Enable UART even parity*/ UART_PARITY_ODD = 0x3 /*!< Enable UART odd parity*/ } uart_parity_t; + +/** + * @brief UART hardware flow control modes + */ +typedef enum { + UART_HW_FLOWCTRL_DISABLE = 0x0, /*!< disable hardware flow control*/ + UART_HW_FLOWCTRL_RTS = 0x1, /*!< enable RX hardware flow control (rts)*/ + UART_HW_FLOWCTRL_CTS = 0x2, /*!< enable TX hardware flow control (cts)*/ + UART_HW_FLOWCTRL_CTS_RTS = 0x3, /*!< enable hardware flow control*/ + UART_HW_FLOWCTRL_MAX = 0x4, +} uart_hw_flowcontrol_t; + +typedef struct { + int baud_rate; /*!< UART baud rate*/ + uart_word_length_t data_bits; /*!< UART byte size*/ + uart_parity_t parity; /*!< UART parity mode*/ + uart_stop_bits_t stop_bits; /*!< UART stop bits*/ + uart_hw_flowcontrol_t flow_ctrl; /*!< UART HW flow control mode (cts/rts)*/ + uint8_t rx_flow_ctrl_thresh; /*!< UART HW RTS threshold*/ + bool use_ref_tick; /*!< Set to true if UART should be clocked from REF_TICK */ +} uart_config_t; + +esp_err_t uart_flush(uart_port_t uart_num); +esp_err_t uart_param_config(uart_port_t uart_num, const uart_config_t* uart_config); +esp_err_t uart_driver_install( + uart_port_t uart_num, int rx_buffer_size, int tx_buffer_size, int queue_size, QueueHandle_t* uart_queue, int intr_alloc_flags); +esp_err_t uart_get_buffered_data_len(uart_port_t uart_num, size_t* size); +int uart_read_bytes(uart_port_t uart_num, uint8_t* buf, uint32_t length, TickType_t ticks_to_wait); +int uart_write_bytes(uart_port_t uart_num, const char* src, size_t size); +esp_err_t uart_set_mode(uart_port_t uart_num, uart_mode_t mode); +esp_err_t uart_set_pin(uart_port_t uart_num, int tx_io_num, int rx_io_num, int rts_io_num, int cts_io_num); +esp_err_t uart_wait_tx_done(uart_port_t uart_num, TickType_t ticks_to_wait); diff --git a/X86TestSupport/esp_err.h b/X86TestSupport/esp_err.h new file mode 100644 index 00000000..9391bcab --- /dev/null +++ b/X86TestSupport/esp_err.h @@ -0,0 +1,154 @@ +// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at + +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#pragma once + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +typedef int esp_err_t; + +/* Definitions for error constants. */ +#define ESP_OK 0 /*!< esp_err_t value indicating success (no error) */ +#define ESP_FAIL -1 /*!< Generic esp_err_t code indicating failure */ + +#define ESP_ERR_NO_MEM 0x101 /*!< Out of memory */ +#define ESP_ERR_INVALID_ARG 0x102 /*!< Invalid argument */ +#define ESP_ERR_INVALID_STATE 0x103 /*!< Invalid state */ +#define ESP_ERR_INVALID_SIZE 0x104 /*!< Invalid size */ +#define ESP_ERR_NOT_FOUND 0x105 /*!< Requested resource not found */ +#define ESP_ERR_NOT_SUPPORTED 0x106 /*!< Operation or feature not supported */ +#define ESP_ERR_TIMEOUT 0x107 /*!< Operation timed out */ +#define ESP_ERR_INVALID_RESPONSE 0x108 /*!< Received response was invalid */ +#define ESP_ERR_INVALID_CRC 0x109 /*!< CRC or checksum was invalid */ +#define ESP_ERR_INVALID_VERSION 0x10A /*!< Version was invalid */ +#define ESP_ERR_INVALID_MAC 0x10B /*!< MAC address was invalid */ +#define ESP_ERR_NOT_FINISHED 0x10C /*!< There are items remained to retrieve */ + +#define ESP_ERR_WIFI_BASE 0x3000 /*!< Starting number of WiFi error codes */ +#define ESP_ERR_MESH_BASE 0x4000 /*!< Starting number of MESH error codes */ +#define ESP_ERR_FLASH_BASE 0x6000 /*!< Starting number of flash error codes */ +#define ESP_ERR_HW_CRYPTO_BASE 0xc000 /*!< Starting number of HW cryptography module error codes */ + +/** + * @brief Returns string for esp_err_t error codes + * + * This function finds the error code in a pre-generated lookup-table and + * returns its string representation. + * + * The function is generated by the Python script + * tools/gen_esp_err_to_name.py which should be run each time an esp_err_t + * error is modified, created or removed from the IDF project. + * + * @param code esp_err_t error code + * @return string error message + */ +const char* esp_err_to_name(esp_err_t code); + +/** + * @brief Returns string for esp_err_t and system error codes + * + * This function finds the error code in a pre-generated lookup-table of + * esp_err_t errors and returns its string representation. If the error code + * is not found then it is attempted to be found among system errors. + * + * The function is generated by the Python script + * tools/gen_esp_err_to_name.py which should be run each time an esp_err_t + * error is modified, created or removed from the IDF project. + * + * @param code esp_err_t error code + * @param[out] buf buffer where the error message should be written + * @param buflen Size of buffer buf. At most buflen bytes are written into the buf buffer (including the terminating null byte). + * @return buf containing the string error message + */ +const char* esp_err_to_name_r(esp_err_t code, char* buf, size_t buflen); + +/** @cond */ +void _esp_error_check_failed(esp_err_t rc, const char* file, int line, const char* function, const char* expression); + +/** @cond */ +void _esp_error_check_failed_without_abort(esp_err_t rc, const char* file, int line, const char* function, const char* expression); + +#ifndef __ASSERT_FUNC +/* This won't happen on IDF, which defines __ASSERT_FUNC in assert.h, but it does happen when building on the host which + uses /usr/include/assert.h or equivalent. +*/ +# ifdef __ASSERT_FUNCTION +# define __ASSERT_FUNC __ASSERT_FUNCTION /* used in glibc assert.h */ +# else +# define __ASSERT_FUNC "??" +# endif +#endif +/** @endcond */ + +/** + * Macro which can be used to check the error code, + * and terminate the program in case the code is not ESP_OK. + * Prints the error code, error location, and the failed statement to serial output. + * + * Disabled if assertions are disabled. + */ +#ifdef NDEBUG +# define ESP_ERROR_CHECK(x) \ + do { \ + esp_err_t err_rc_ = (x); \ + (void)sizeof(err_rc_); \ + } while (0) +#elif defined(CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT) +# define ESP_ERROR_CHECK(x) \ + do { \ + esp_err_t err_rc_ = (x); \ + if (unlikely(err_rc_ != ESP_OK)) { \ + abort(); \ + } \ + } while (0) +#else +# define ESP_ERROR_CHECK(x) \ + do { \ + esp_err_t err_rc_ = (x); \ + if (unlikely(err_rc_ != ESP_OK)) { \ + _esp_error_check_failed(err_rc_, __FILE__, __LINE__, __ASSERT_FUNC, #x); \ + } \ + } while (0) +#endif + +/** + * Macro which can be used to check the error code. Prints the error code, error location, and the failed statement to + * serial output. + * In comparison with ESP_ERROR_CHECK(), this prints the same error message but isn't terminating the program. + */ +#ifdef NDEBUG +# define ESP_ERROR_CHECK_WITHOUT_ABORT(x) \ + ({ \ + esp_err_t err_rc_ = (x); \ + err_rc_; \ + }) +#else +# define ESP_ERROR_CHECK_WITHOUT_ABORT(x) \ + ({ \ + esp_err_t err_rc_ = (x); \ + if (unlikely(err_rc_ != ESP_OK)) { \ + _esp_error_check_failed_without_abort(err_rc_, __FILE__, __LINE__, __ASSERT_FUNC, #x); \ + } \ + err_rc_; \ + }) +#endif //NDEBUG + +#ifdef __cplusplus +} +#endif diff --git a/X86TestSupport/esp_system.h b/X86TestSupport/esp_system.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/esp_system.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/freertos/FreeRTOS.h b/X86TestSupport/freertos/FreeRTOS.h new file mode 100644 index 00000000..2a6f337b --- /dev/null +++ b/X86TestSupport/freertos/FreeRTOS.h @@ -0,0 +1,32 @@ +#pragma once + +#include "Task.h" +#include "Queue.h" + +/* "mux" data structure (spinlock) */ +typedef struct { + /* owner field values: + * 0 - Uninitialized (invalid) + * portMUX_FREE_VAL - Mux is free, can be locked by either CPU + * CORE_ID_PRO / CORE_ID_APP - Mux is locked to the particular core + * + * Any value other than portMUX_FREE_VAL, CORE_ID_PRO, CORE_ID_APP indicates corruption + */ + uint32_t owner; + /* count field: + * If mux is unlocked, count should be zero. + * If mux is locked, count is non-zero & represents the number of recursive locks on the mux. + */ + uint32_t count; +#ifdef CONFIG_FREERTOS_PORTMUX_DEBUG + const char* lastLockedFn; + int lastLockedLine; +#endif +} portMUX_TYPE; + +#define portMAX_DELAY (TickType_t)0xffffffffUL + +void vTaskExitCritical(portMUX_TYPE* mux); +void vTaskEnterCritical(portMUX_TYPE* mux); + +int32_t xPortGetFreeHeapSize(); diff --git a/X86TestSupport/freertos/Queue.h b/X86TestSupport/freertos/Queue.h new file mode 100644 index 00000000..498d8763 --- /dev/null +++ b/X86TestSupport/freertos/Queue.h @@ -0,0 +1,39 @@ +#pragma once + +#include "task.h" + +typedef void* QueueHandle_t; + +using xQueueHandle = QueueHandle_t; + +#define queueSEND_TO_BACK ((BaseType_t)0) +#define queueSEND_TO_FRONT ((BaseType_t)1) +#define queueOVERWRITE ((BaseType_t)2) + +BaseType_t xQueueGenericReceive(QueueHandle_t xQueue, void* const pvBuffer, TickType_t xTicksToWait, const BaseType_t xJustPeek); + +BaseType_t xQueueGenericSendFromISR(QueueHandle_t xQueue, + const void* const pvItemToQueue, + BaseType_t* const pxHigherPriorityTaskWoken, + const BaseType_t xCopyPosition); + +QueueHandle_t xQueueGenericCreate(const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType); + +BaseType_t xQueueGenericReset(QueueHandle_t xQueue, BaseType_t xNewQueue); + +BaseType_t xQueueGenericSend(QueueHandle_t xQueue, const void* const pvItemToQueue, TickType_t xTicksToWait, BaseType_t xCopyPosition); + +#define xQueueSendFromISR(xQueue, pvItemToQueue, pxHigherPriorityTaskWoken) \ + xQueueGenericSendFromISR((xQueue), (pvItemToQueue), (pxHigherPriorityTaskWoken), queueSEND_TO_BACK) + +#define pdFALSE ((BaseType_t)0) +#define pdTRUE ((BaseType_t)1) +#define xQueueReceive(xQueue, pvBuffer, xTicksToWait) xQueueGenericReceive((xQueue), (pvBuffer), (xTicksToWait), pdFALSE) + +#define queueQUEUE_TYPE_BASE ((uint8_t)0U) + +#define xQueueCreate(uxQueueLength, uxItemSize) xQueueGenericCreate((uxQueueLength), (uxItemSize), (queueQUEUE_TYPE_BASE)) + +#define xQueueReset(xQueue) xQueueGenericReset(xQueue, pdFALSE) + +#define xQueueSend(xQueue, pvItemToQueue, xTicksToWait) xQueueGenericSend((xQueue), (pvItemToQueue), (xTicksToWait), queueSEND_TO_BACK) diff --git a/X86TestSupport/freertos/task.h b/X86TestSupport/freertos/task.h new file mode 100644 index 00000000..b66247f4 --- /dev/null +++ b/X86TestSupport/freertos/task.h @@ -0,0 +1,59 @@ +#pragma once + +#include "../Arduino.h" +#include "FreeRTOS.h" + +#define portBASE_TYPE int +typedef unsigned portBASE_TYPE UBaseType_t; +typedef portBASE_TYPE BaseType_t; +typedef uint32_t TickType_t; + +void vTaskDelay(const TickType_t xTicksToDelay); + +typedef void (*TaskFunction_t)(void*); +typedef void* TaskHandle_t; + +#define CONFIG_ARDUINO_RUNNING_CORE 0 + +BaseType_t xTaskCreatePinnedToCore(TaskFunction_t pvTaskCode, + const char* const pcName, + const uint32_t usStackDepth, + void* const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t* const pvCreatedTask, + const BaseType_t xCoreID); + +#define tskNO_AFFINITY INT_MAX + +static inline IRAM_ATTR BaseType_t xTaskCreate(TaskFunction_t pvTaskCode, + const char* const pcName, + const uint32_t usStackDepth, + void* const pvParameters, + UBaseType_t uxPriority, + TaskHandle_t* const pvCreatedTask) { + return xTaskCreatePinnedToCore(pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pvCreatedTask, tskNO_AFFINITY); +} + +void vTaskDelayUntil(TickType_t* const pxPreviousWakeTime, const TickType_t xTimeIncrement); + +TickType_t xTaskGetTickCount(void); + +#define CONFIG_FREERTOS_HZ 1000 +#define configTICK_RATE_HZ (CONFIG_FREERTOS_HZ) +#define portTICK_PERIOD_MS ((TickType_t)1000 / configTICK_RATE_HZ) +#define portTICK_RATE_MS portTICK_PERIOD_MS + +#define portMUX_FREE_VAL 0xB33FFFFF + +/* Special constants for vPortCPUAcquireMutexTimeout() */ +#define portMUX_NO_TIMEOUT (-1) /* When passed for 'timeout_cycles', spin forever if necessary */ +#define portMUX_TRY_LOCK 0 /* Try to acquire the spinlock a single time only */ + +// Keep this in sync with the portMUX_TYPE struct definition please. +#ifndef CONFIG_FREERTOS_PORTMUX_DEBUG +# define portMUX_INITIALIZER_UNLOCKED \ + { .owner = portMUX_FREE_VAL, .count = 0, } +#else +# define portMUX_INITIALIZER_UNLOCKED \ + { .owner = portMUX_FREE_VAL, .count = 0, .lastLockedFn = "(never locked)", .lastLockedLine = -1 } +#endif diff --git a/X86TestSupport/nvs.h b/X86TestSupport/nvs.h new file mode 100644 index 00000000..5d9851dc --- /dev/null +++ b/X86TestSupport/nvs.h @@ -0,0 +1,163 @@ +#pragma once + +#include + +class NvsEmulator { + // NVS is basically a key-value store. + +public: + std::unordered_map data; + + bool tryGetI32(const char* str, int32_t& value) { + auto it = data.find(str); + if (it != data.end() && it->second.size() == 4) { + value = *reinterpret_cast(it->second.data()); + return true; + } else { + return false; + } + } + + bool tryGetI8(const char* str, int8_t& value) { + auto it = data.find(str); + if (it != data.end() && it->second.size() == 1) { + value = *reinterpret_cast(it->second.data()); + return true; + } else { + return false; + } + } + + bool tryGetStr(const char* str, char* buf, int32_t& len) { + auto it = data.find(str); + if (it != data.end()) { + auto v = int32_t(it->second.size()); + if (buf) { + if (v > len) { + v = len; + } + memcpy(buf, it->second.c_str(), v + 1); + len = v; + } else { + len = v; + } + return true; + } else { + return false; + } + } + + bool tryGetBlob(const char* str, char* buf, int32_t& len) { + auto it = data.find(str); + if (it != data.end()) { + auto v = int32_t(it->second.size()); + if (buf) { + if (v > len) { + v = len; + } + memcpy(buf, it->second.c_str(), v); + len = v; + } else { + len = v; + } + return true; + } else { + return false; + } + } + + void erase(const char* str) { + auto it = data.find(str); + if (it != data.end()) { + data.erase(it); + } + } + + void clear() { data.clear(); } + + static NvsEmulator& instance() { + static NvsEmulator instance; + return instance; + } +}; + +struct nvs_stats_t { + int used_entries; + int free_entries; + int total_entries; +}; + +using nvs_handle = NvsEmulator*; + +inline esp_err_t nvs_get_stats(const char* part_name, nvs_stats_t* stats) { + auto& inst = NvsEmulator::instance(); + stats->used_entries = inst.data.size(); + stats->free_entries = 1000 - inst.data.size(); + stats->total_entries = 1024; + return ESP_OK; +} + +inline esp_err_t nvs_erase_all(nvs_handle handle) { + handle->clear(); + return ESP_OK; +} + +enum nvs_open_mode { NVS_READWRITE }; + +#define ESP_ERR_NVS_BASE 0x1100 /*!< Starting number of error codes */ +#define ESP_ERR_NVS_NOT_INITIALIZED (ESP_ERR_NVS_BASE + 0x01) /*!< The storage driver is not initialized */ +#define ESP_ERR_NVS_NOT_FOUND (ESP_ERR_NVS_BASE + 0x02) /*!< Id namespace doesn’t exist yet and mode is NVS_READONLY */ +#define ESP_ERR_NVS_TYPE_MISMATCH \ + (ESP_ERR_NVS_BASE + 0x03) /*!< The type of set or get operation doesn't match the type of value stored in NVS */ +#define ESP_ERR_NVS_READ_ONLY (ESP_ERR_NVS_BASE + 0x04) /*!< Storage handle was opened as read only */ +#define ESP_ERR_NVS_NOT_ENOUGH_SPACE (ESP_ERR_NVS_BASE + 0x05) /*!< There is not enough space in the underlying storage to save the value */ +#define ESP_ERR_NVS_INVALID_NAME (ESP_ERR_NVS_BASE + 0x06) /*!< Namespace name doesn’t satisfy constraints */ +#define ESP_ERR_NVS_INVALID_HANDLE (ESP_ERR_NVS_BASE + 0x07) /*!< Handle has been closed or is NULL */ +#define ESP_ERR_NVS_REMOVE_FAILED \ + (ESP_ERR_NVS_BASE + \ + 0x08) /*!< The value wasn’t updated because flash write operation has failed. The value was written however, and update will be finished after re-initialization of nvs, provided that flash operation doesn’t fail again. */ +#define ESP_ERR_NVS_KEY_TOO_LONG (ESP_ERR_NVS_BASE + 0x09) /*!< Key name is too long */ +#define ESP_ERR_NVS_PAGE_FULL (ESP_ERR_NVS_BASE + 0x0a) /*!< Internal error; never returned by nvs API functions */ +#define ESP_ERR_NVS_INVALID_STATE \ + (ESP_ERR_NVS_BASE + \ + 0x0b) /*!< NVS is in an inconsistent state due to a previous error. Call nvs_flash_init and nvs_open again, then retry. */ +#define ESP_ERR_NVS_INVALID_LENGTH (ESP_ERR_NVS_BASE + 0x0c) /*!< String or blob length is not sufficient to store data */ +#define ESP_ERR_NVS_NO_FREE_PAGES \ + (ESP_ERR_NVS_BASE + \ + 0x0d) /*!< NVS partition doesn't contain any empty pages. This may happen if NVS partition was truncated. Erase the whole partition and call nvs_flash_init again. */ +#define ESP_ERR_NVS_VALUE_TOO_LONG (ESP_ERR_NVS_BASE + 0x0e) /*!< String or blob length is longer than supported by the implementation */ +#define ESP_ERR_NVS_PART_NOT_FOUND (ESP_ERR_NVS_BASE + 0x0f) /*!< Partition with specified name is not found in the partition table */ + +#define ESP_ERR_NVS_NEW_VERSION_FOUND \ + (ESP_ERR_NVS_BASE + 0x10) /*!< NVS partition contains data in new format and cannot be recognized by this version of code */ +#define ESP_ERR_NVS_XTS_ENCR_FAILED (ESP_ERR_NVS_BASE + 0x11) /*!< XTS encryption failed while writing NVS entry */ +#define ESP_ERR_NVS_XTS_DECR_FAILED (ESP_ERR_NVS_BASE + 0x12) /*!< XTS decryption failed while reading NVS entry */ +#define ESP_ERR_NVS_XTS_CFG_FAILED (ESP_ERR_NVS_BASE + 0x13) /*!< XTS configuration setting failed */ +#define ESP_ERR_NVS_XTS_CFG_NOT_FOUND (ESP_ERR_NVS_BASE + 0x14) /*!< XTS configuration not found */ +#define ESP_ERR_NVS_ENCR_NOT_SUPPORTED (ESP_ERR_NVS_BASE + 0x15) /*!< NVS encryption is not supported in this version */ +#define ESP_ERR_NVS_KEYS_NOT_INITIALIZED (ESP_ERR_NVS_BASE + 0x16) /*!< NVS key partition is uninitialized */ +#define ESP_ERR_NVS_CORRUPT_KEY_PART (ESP_ERR_NVS_BASE + 0x17) /*!< NVS key partition is corrupt */ +#define ESP_ERR_NVS_WRONG_ENCRYPTION \ + (ESP_ERR_NVS_BASE + \ + 0x19) /*!< NVS partition is marked as encrypted with generic flash encryption. This is forbidden since the NVS encryption works differently. */ + +#define ESP_ERR_NVS_CONTENT_DIFFERS \ + (ESP_ERR_NVS_BASE + 0x18) /*!< Internal error; never returned by nvs API functions. NVS key is different in comparison */ + +#define NVS_DEFAULT_PART_NAME "nvs" /*!< Default partition name of the NVS partition in the partition table */ + +#define NVS_PART_NAME_MAX_SIZE 16 /*!< maximum length of partition name (excluding null terminator) */ +#define NVS_KEY_NAME_MAX_SIZE 16 /*!< Maximal length of NVS key name (including null terminator) */ + +esp_err_t nvs_open(const char* name, nvs_open_mode open_mode, nvs_handle* out_handle); +esp_err_t nvs_get_i32(nvs_handle handle, const char* key, int32_t* out_value); +esp_err_t nvs_get_i8(nvs_handle handle, const char* key, int8_t* out_value); +esp_err_t nvs_get_str(nvs_handle handle, const char* key, char* out_value, size_t* length); +esp_err_t nvs_get_blob(nvs_handle handle, const char* key, void* out_value, size_t* length); +esp_err_t nvs_erase_key(nvs_handle handle, const char* key); +esp_err_t nvs_erase_all(nvs_handle handle); + +esp_err_t nvs_set_i8(nvs_handle handle, const char* key, int32_t value); +esp_err_t nvs_set_i32(nvs_handle handle, const char* key, int32_t value); +esp_err_t nvs_set_str(nvs_handle handle, const char* key, const char* value); +esp_err_t nvs_set_blob(nvs_handle handle, const char* key, const void* value, size_t length); diff --git a/X86TestSupport/soc/dport_reg.h b/X86TestSupport/soc/dport_reg.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/soc/dport_reg.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/soc/gpio_sig_map.h b/X86TestSupport/soc/gpio_sig_map.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/soc/gpio_sig_map.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/soc/io_mux_reg.h b/X86TestSupport/soc/io_mux_reg.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/soc/io_mux_reg.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/soc/ledc_struct.h b/X86TestSupport/soc/ledc_struct.h new file mode 100644 index 00000000..1b36807c --- /dev/null +++ b/X86TestSupport/soc/ledc_struct.h @@ -0,0 +1,245 @@ +#pragma once + +// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at + +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#define LEDC_HS_SIG_OUT0_IDX 71 +#define LEDC_LS_SIG_OUT0_IDX 79 + +typedef volatile struct { + struct { + struct { + union { + struct { + uint32_t timer_sel : 2; /*There are four high speed timers the two bits are used to select one of them for high speed channel. 2'b00: seletc hstimer0. 2'b01: select hstimer1. 2'b10: select hstimer2. 2'b11: select hstimer3.*/ + uint32_t sig_out_en : 1; /*This is the output enable control bit for high speed channel*/ + uint32_t idle_lv : 1; /*This bit is used to control the output value when high speed channel is off.*/ + uint32_t reserved4 : 27; + uint32_t clk_en : 1; /*This bit is clock gating control signal. when software configure LED_PWM internal registers it controls the register clock.*/ + }; + uint32_t val; + } conf0; + union { + struct { + uint32_t hpoint : 20; /*The output value changes to high when htimerx(x=[0 3]) selected by high speed channel has reached reg_hpoint_hsch0[19:0]*/ + uint32_t reserved20 : 12; + }; + uint32_t val; + } hpoint; + union { + struct { + uint32_t duty : 25; /*The register is used to control output duty. When hstimerx(x=[0 3]) chosen by high speed channel has reached reg_lpoint_hsch0 the output signal changes to low. reg_lpoint_hsch0=(reg_hpoint_hsch0[19:0]+reg_duty_hsch0[24:4]) (1) reg_lpoint_hsch0=(reg_hpoint_hsch0[19:0]+reg_duty_hsch0[24:4] +1) (2) The least four bits in this register represent the decimal part and determines when to choose (1) or (2)*/ + uint32_t reserved25 : 7; + }; + uint32_t val; + } duty; + union { + struct { + uint32_t duty_scale : 10; /*This register controls the increase or decrease step scale for high speed channel.*/ + uint32_t duty_cycle : 10; /*This register is used to increase or decrease the duty every reg_duty_cycle_hsch0 cycles for high speed channel.*/ + uint32_t duty_num : 10; /*This register is used to control the number of increased or decreased times for high speed channel.*/ + uint32_t duty_inc : 1; /*This register is used to increase the duty of output signal or decrease the duty of output signal for high speed channel.*/ + uint32_t duty_start : 1; /*When reg_duty_num_hsch0 reg_duty_cycle_hsch0 and reg_duty_scale_hsch0 has been configured. these register won't take effect until set reg_duty_start_hsch0. this bit is automatically cleared by hardware.*/ + }; + uint32_t val; + } conf1; + union { + struct { + uint32_t duty_read : 25; /*This register represents the current duty of the output signal for high speed channel.*/ + uint32_t reserved25 : 7; + }; + uint32_t val; + } duty_rd; + } channel[8]; + } channel_group[2]; /*two channel groups : 0: high-speed channels; 1: low-speed channels*/ + struct { + struct { + union { + struct { + uint32_t bit_num : 5; /*This register controls the range of the counter in high speed timer. the counter range is [0 2**reg_hstimer0_lim] the max bit width for counter is 20.*/ + uint32_t div_num : 18; /*This register is used to configure parameter for divider in high speed timer the least significant eight bits represent the decimal part.*/ + uint32_t pause : 1; /*This bit is used to pause the counter in high speed timer*/ + uint32_t rst : 1; /*This bit is used to reset high speed timer the counter will be 0 after reset.*/ + uint32_t tick_sel : 1; /*This bit is used to choose apb_clk or ref_tick for high speed timer. 1'b1:apb_clk 0:ref_tick*/ + uint32_t low_speed_update : 1; /*This bit is only useful for low speed timer channels, reserved for high speed timers*/ + uint32_t reserved26 : 5; + }; + uint32_t val; + } conf; + union { + struct { + uint32_t timer_cnt : 20; /*software can read this register to get the current counter value in high speed timer*/ + uint32_t reserved20 : 12; + }; + uint32_t val; + } value; + } timer[4]; + } timer_group[2]; /*two channel groups : 0: high-speed channels; 1: low-speed channels*/ + union { + struct { + uint32_t hstimer0_ovf : 1; /*The interrupt raw bit for high speed channel0 counter overflow.*/ + uint32_t hstimer1_ovf : 1; /*The interrupt raw bit for high speed channel1 counter overflow.*/ + uint32_t hstimer2_ovf : 1; /*The interrupt raw bit for high speed channel2 counter overflow.*/ + uint32_t hstimer3_ovf : 1; /*The interrupt raw bit for high speed channel3 counter overflow.*/ + uint32_t lstimer0_ovf : 1; /*The interrupt raw bit for low speed channel0 counter overflow.*/ + uint32_t lstimer1_ovf : 1; /*The interrupt raw bit for low speed channel1 counter overflow.*/ + uint32_t lstimer2_ovf : 1; /*The interrupt raw bit for low speed channel2 counter overflow.*/ + uint32_t lstimer3_ovf : 1; /*The interrupt raw bit for low speed channel3 counter overflow.*/ + uint32_t duty_chng_end_hsch0 : 1; /*The interrupt raw bit for high speed channel 0 duty change done.*/ + uint32_t duty_chng_end_hsch1 : 1; /*The interrupt raw bit for high speed channel 1 duty change done.*/ + uint32_t duty_chng_end_hsch2 : 1; /*The interrupt raw bit for high speed channel 2 duty change done.*/ + uint32_t duty_chng_end_hsch3 : 1; /*The interrupt raw bit for high speed channel 3 duty change done.*/ + uint32_t duty_chng_end_hsch4 : 1; /*The interrupt raw bit for high speed channel 4 duty change done.*/ + uint32_t duty_chng_end_hsch5 : 1; /*The interrupt raw bit for high speed channel 5 duty change done.*/ + uint32_t duty_chng_end_hsch6 : 1; /*The interrupt raw bit for high speed channel 6 duty change done.*/ + uint32_t duty_chng_end_hsch7 : 1; /*The interrupt raw bit for high speed channel 7 duty change done.*/ + uint32_t duty_chng_end_lsch0 : 1; /*The interrupt raw bit for low speed channel 0 duty change done.*/ + uint32_t duty_chng_end_lsch1 : 1; /*The interrupt raw bit for low speed channel 1 duty change done.*/ + uint32_t duty_chng_end_lsch2 : 1; /*The interrupt raw bit for low speed channel 2 duty change done.*/ + uint32_t duty_chng_end_lsch3 : 1; /*The interrupt raw bit for low speed channel 3 duty change done.*/ + uint32_t duty_chng_end_lsch4 : 1; /*The interrupt raw bit for low speed channel 4 duty change done.*/ + uint32_t duty_chng_end_lsch5 : 1; /*The interrupt raw bit for low speed channel 5 duty change done.*/ + uint32_t duty_chng_end_lsch6 : 1; /*The interrupt raw bit for low speed channel 6 duty change done.*/ + uint32_t duty_chng_end_lsch7 : 1; /*The interrupt raw bit for low speed channel 7 duty change done.*/ + uint32_t reserved24 : 8; + }; + uint32_t val; + } int_raw; + union { + struct { + uint32_t hstimer0_ovf : 1; /*The interrupt status bit for high speed channel0 counter overflow event.*/ + uint32_t hstimer1_ovf : 1; /*The interrupt status bit for high speed channel1 counter overflow event.*/ + uint32_t hstimer2_ovf : 1; /*The interrupt status bit for high speed channel2 counter overflow event.*/ + uint32_t hstimer3_ovf : 1; /*The interrupt status bit for high speed channel3 counter overflow event.*/ + uint32_t lstimer0_ovf : 1; /*The interrupt status bit for low speed channel0 counter overflow event.*/ + uint32_t lstimer1_ovf : 1; /*The interrupt status bit for low speed channel1 counter overflow event.*/ + uint32_t lstimer2_ovf : 1; /*The interrupt status bit for low speed channel2 counter overflow event.*/ + uint32_t lstimer3_ovf : 1; /*The interrupt status bit for low speed channel3 counter overflow event.*/ + uint32_t duty_chng_end_hsch0 : 1; /*The interrupt enable bit for high speed channel 0 duty change done event.*/ + uint32_t duty_chng_end_hsch1 : 1; /*The interrupt status bit for high speed channel 1 duty change done event.*/ + uint32_t duty_chng_end_hsch2 : 1; /*The interrupt status bit for high speed channel 2 duty change done event.*/ + uint32_t duty_chng_end_hsch3 : 1; /*The interrupt status bit for high speed channel 3 duty change done event.*/ + uint32_t duty_chng_end_hsch4 : 1; /*The interrupt status bit for high speed channel 4 duty change done event.*/ + uint32_t duty_chng_end_hsch5 : 1; /*The interrupt status bit for high speed channel 5 duty change done event.*/ + uint32_t duty_chng_end_hsch6 : 1; /*The interrupt status bit for high speed channel 6 duty change done event.*/ + uint32_t duty_chng_end_hsch7 : 1; /*The interrupt status bit for high speed channel 7 duty change done event.*/ + uint32_t duty_chng_end_lsch0 : 1; /*The interrupt status bit for low speed channel 0 duty change done event.*/ + uint32_t duty_chng_end_lsch1 : 1; /*The interrupt status bit for low speed channel 1 duty change done event.*/ + uint32_t duty_chng_end_lsch2 : 1; /*The interrupt status bit for low speed channel 2 duty change done event.*/ + uint32_t duty_chng_end_lsch3 : 1; /*The interrupt status bit for low speed channel 3 duty change done event.*/ + uint32_t duty_chng_end_lsch4 : 1; /*The interrupt status bit for low speed channel 4 duty change done event.*/ + uint32_t duty_chng_end_lsch5 : 1; /*The interrupt status bit for low speed channel 5 duty change done event.*/ + uint32_t duty_chng_end_lsch6 : 1; /*The interrupt status bit for low speed channel 6 duty change done event.*/ + uint32_t duty_chng_end_lsch7 : 1; /*The interrupt status bit for low speed channel 7 duty change done event*/ + uint32_t reserved24 : 8; + }; + uint32_t val; + } int_st; + union { + struct { + uint32_t hstimer0_ovf : 1; /*The interrupt enable bit for high speed channel0 counter overflow interrupt.*/ + uint32_t hstimer1_ovf : 1; /*The interrupt enable bit for high speed channel1 counter overflow interrupt.*/ + uint32_t hstimer2_ovf : 1; /*The interrupt enable bit for high speed channel2 counter overflow interrupt.*/ + uint32_t hstimer3_ovf : 1; /*The interrupt enable bit for high speed channel3 counter overflow interrupt.*/ + uint32_t lstimer0_ovf : 1; /*The interrupt enable bit for low speed channel0 counter overflow interrupt.*/ + uint32_t lstimer1_ovf : 1; /*The interrupt enable bit for low speed channel1 counter overflow interrupt.*/ + uint32_t lstimer2_ovf : 1; /*The interrupt enable bit for low speed channel2 counter overflow interrupt.*/ + uint32_t lstimer3_ovf : 1; /*The interrupt enable bit for low speed channel3 counter overflow interrupt.*/ + uint32_t duty_chng_end_hsch0 : 1; /*The interrupt enable bit for high speed channel 0 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch1 : 1; /*The interrupt enable bit for high speed channel 1 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch2 : 1; /*The interrupt enable bit for high speed channel 2 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch3 : 1; /*The interrupt enable bit for high speed channel 3 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch4 : 1; /*The interrupt enable bit for high speed channel 4 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch5 : 1; /*The interrupt enable bit for high speed channel 5 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch6 : 1; /*The interrupt enable bit for high speed channel 6 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch7 : 1; /*The interrupt enable bit for high speed channel 7 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch0 : 1; /*The interrupt enable bit for low speed channel 0 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch1 : 1; /*The interrupt enable bit for low speed channel 1 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch2 : 1; /*The interrupt enable bit for low speed channel 2 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch3 : 1; /*The interrupt enable bit for low speed channel 3 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch4 : 1; /*The interrupt enable bit for low speed channel 4 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch5 : 1; /*The interrupt enable bit for low speed channel 5 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch6 : 1; /*The interrupt enable bit for low speed channel 6 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch7 : 1; /*The interrupt enable bit for low speed channel 7 duty change done interrupt.*/ + uint32_t reserved24 : 8; + }; + uint32_t val; + } int_ena; + union { + struct { + uint32_t hstimer0_ovf : 1; /*Set this bit to clear high speed channel0 counter overflow interrupt.*/ + uint32_t hstimer1_ovf : 1; /*Set this bit to clear high speed channel1 counter overflow interrupt.*/ + uint32_t hstimer2_ovf : 1; /*Set this bit to clear high speed channel2 counter overflow interrupt.*/ + uint32_t hstimer3_ovf : 1; /*Set this bit to clear high speed channel3 counter overflow interrupt.*/ + uint32_t lstimer0_ovf : 1; /*Set this bit to clear low speed channel0 counter overflow interrupt.*/ + uint32_t lstimer1_ovf : 1; /*Set this bit to clear low speed channel1 counter overflow interrupt.*/ + uint32_t lstimer2_ovf : 1; /*Set this bit to clear low speed channel2 counter overflow interrupt.*/ + uint32_t lstimer3_ovf : 1; /*Set this bit to clear low speed channel3 counter overflow interrupt.*/ + uint32_t duty_chng_end_hsch0 : 1; /*Set this bit to clear high speed channel 0 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch1 : 1; /*Set this bit to clear high speed channel 1 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch2 : 1; /*Set this bit to clear high speed channel 2 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch3 : 1; /*Set this bit to clear high speed channel 3 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch4 : 1; /*Set this bit to clear high speed channel 4 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch5 : 1; /*Set this bit to clear high speed channel 5 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch6 : 1; /*Set this bit to clear high speed channel 6 duty change done interrupt.*/ + uint32_t duty_chng_end_hsch7 : 1; /*Set this bit to clear high speed channel 7 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch0 : 1; /*Set this bit to clear low speed channel 0 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch1 : 1; /*Set this bit to clear low speed channel 1 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch2 : 1; /*Set this bit to clear low speed channel 2 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch3 : 1; /*Set this bit to clear low speed channel 3 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch4 : 1; /*Set this bit to clear low speed channel 4 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch5 : 1; /*Set this bit to clear low speed channel 5 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch6 : 1; /*Set this bit to clear low speed channel 6 duty change done interrupt.*/ + uint32_t duty_chng_end_lsch7 : 1; /*Set this bit to clear low speed channel 7 duty change done interrupt.*/ + uint32_t reserved24 : 8; + }; + uint32_t val; + } int_clr; + union { + struct { + uint32_t apb_clk_sel : 1; /*This bit is used to set the frequency of slow_clk. 1'b1:80mhz 1'b0:8mhz*/ + uint32_t reserved1 : 31; + }; + uint32_t val; + } conf; + uint32_t reserved_194; + uint32_t reserved_198; + uint32_t reserved_19c; + uint32_t reserved_1a0; + uint32_t reserved_1a4; + uint32_t reserved_1a8; + uint32_t reserved_1ac; + uint32_t reserved_1b0; + uint32_t reserved_1b4; + uint32_t reserved_1b8; + uint32_t reserved_1bc; + uint32_t reserved_1c0; + uint32_t reserved_1c4; + uint32_t reserved_1c8; + uint32_t reserved_1cc; + uint32_t reserved_1d0; + uint32_t reserved_1d4; + uint32_t reserved_1d8; + uint32_t reserved_1dc; + uint32_t reserved_1e0; + uint32_t reserved_1e4; + uint32_t reserved_1e8; + uint32_t reserved_1ec; + uint32_t reserved_1f0; + uint32_t reserved_1f4; + uint32_t reserved_1f8; + uint32_t date; /*This register represents the version .*/ +} ledc_dev_t; + +extern ledc_dev_t LEDC; diff --git a/X86TestSupport/soc/rtc.h b/X86TestSupport/soc/rtc.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/soc/rtc.h @@ -0,0 +1 @@ +#pragma once diff --git a/X86TestSupport/soc/uart_reg.h b/X86TestSupport/soc/uart_reg.h new file mode 100644 index 00000000..6f70f09b --- /dev/null +++ b/X86TestSupport/soc/uart_reg.h @@ -0,0 +1 @@ +#pragma once