├── .gitignore ├── Config.h ├── Extended.config.h ├── LICENSE ├── README.md ├── SmartWebServer.ino └── src ├── Common.h ├── Config.defaults.h ├── Constants.h ├── HAL ├── HAL.h ├── arduinoM0 │ └── ArduinoM0.h ├── atmel │ ├── Mega2560.h │ └── Mega328.h ├── default │ └── Default.h ├── esp │ ├── ESP32Libraries1.h │ ├── ESP32Libraries2.h │ ├── ESP32Libraries3.h │ ├── ESP32UnoR4WiFi.h │ └── ESP8266.h ├── mbed │ ├── Rpi2040.h │ └── Rpi2350.h ├── stm32 │ ├── STM32F103.h │ ├── STM32F303.h │ ├── STM32F407.h │ ├── STM32F446.h │ ├── STM32F4x1.h │ └── STM32H7xx.h └── teensy │ ├── Teensy3.2.h │ ├── Teensy3.5.h │ ├── Teensy3.6.h │ ├── Teensy4.0.h │ └── Teensy4.1.h ├── Validate.h ├── lib ├── 1wire │ ├── 1Wire.cpp │ └── 1Wire.h ├── Constants.h ├── Macros.h ├── analog │ ├── AN_ESP32.cpp │ └── AN_ESP32.h ├── axis │ ├── Axis.command.cpp │ ├── Axis.cpp │ ├── Axis.h │ └── motor │ │ ├── Drivers.h │ │ ├── Motor.cpp │ │ ├── Motor.h │ │ ├── kTech │ │ ├── KTech.cpp │ │ └── KTech.h │ │ ├── oDrive │ │ ├── ODrive.cpp │ │ ├── ODrive.h │ │ └── ODrive.ino │ │ ├── servo │ │ ├── Servo.cpp │ │ ├── Servo.h │ │ ├── Servo.ino │ │ ├── ServoCalibrate.cpp │ │ ├── ServoDriver.cpp │ │ ├── ServoDriver.h │ │ ├── dc │ │ │ ├── Dc.cpp │ │ │ └── Dc.h │ │ ├── dcTmcSPI │ │ │ ├── DcTmcSPI.cpp │ │ │ └── DcTmcSPI.h │ │ ├── feedback │ │ │ ├── Feedback.h │ │ │ ├── FeedbackBase.cpp │ │ │ ├── FeedbackBase.h │ │ │ └── Pid │ │ │ │ ├── Pid.cpp │ │ │ │ └── Pid.h │ │ ├── filter │ │ │ ├── Filter.h │ │ │ ├── FilterBase.cpp │ │ │ ├── FilterBase.h │ │ │ ├── Kalman │ │ │ │ ├── Kalman.cpp │ │ │ │ └── Kalman.h │ │ │ ├── Learning │ │ │ │ ├── Learning.cpp │ │ │ │ └── Learning.h │ │ │ ├── Rolling │ │ │ │ ├── Rolling.cpp │ │ │ │ └── Rolling.h │ │ │ └── Windowing │ │ │ │ ├── Windowing.cpp │ │ │ │ └── Windowing.h │ │ ├── kTech │ │ │ ├── KTech.cpp │ │ │ └── KTech.h │ │ ├── tmc2209 │ │ │ ├── Tmc2209.cpp │ │ │ └── Tmc2209.h │ │ └── tmc5160 │ │ │ ├── Tmc5160.cpp │ │ │ └── Tmc5160.h │ │ └── stepDir │ │ ├── StepDir.cpp │ │ ├── StepDir.h │ │ ├── StepDirDriver.cpp │ │ ├── StepDirDriver.h │ │ ├── generic │ │ ├── Generic.cpp │ │ └── Generic.h │ │ ├── tmcLegacy │ │ ├── LegacySPI.cpp │ │ ├── LegacySPI.h │ │ ├── LegacyUART.cpp │ │ ├── LegacyUART.h │ │ ├── TmcSPI.cpp │ │ └── TmcSPI.h │ │ └── tmcStepper │ │ ├── StepperSPI.cpp │ │ ├── StepperSPI.h │ │ ├── StepperUART.cpp │ │ └── StepperUART.h ├── bluetooth │ ├── Bluetooth.defaults.h │ ├── BluetoothManager.cpp │ └── BluetoothManager.h ├── calendars │ ├── Calendars.cpp │ └── Calendars.h ├── canPlus │ ├── CanPlus.h │ ├── CanPlusBase.cpp │ ├── CanPlusBase.h │ ├── esp32 │ │ ├── Esp32.cpp │ │ └── Esp32.h │ ├── mcp2515 │ │ ├── Mcp2515.cpp │ │ └── Mcp2515.h │ ├── san │ │ ├── San.cpp │ │ └── San.h │ └── teensy4 │ │ ├── Can0.cpp │ │ ├── Can0.h │ │ ├── Can1.cpp │ │ ├── Can1.h │ │ ├── Can2.cpp │ │ ├── Can2.h │ │ ├── Can3.cpp │ │ └── Can3.h ├── commands │ ├── BufferCmds.cpp │ ├── BufferCmds.h │ ├── CommandErrors.h │ ├── SerialWrapper.cpp │ ├── SerialWrapper.h │ └── commands.ino ├── convert │ ├── Convert.cpp │ └── Convert.h ├── debug │ ├── Debug.cpp │ └── Debug.h ├── encoder │ ├── Encoder.h │ ├── EncoderBase.cpp │ ├── EncoderBase.h │ ├── bissc │ │ ├── As37h39bb.cpp │ │ ├── As37h39bb.h │ │ ├── Asc85.cpp │ │ ├── Asc85.h │ │ ├── Bissc.cpp │ │ ├── Bissc.h │ │ ├── Jtw24.cpp │ │ ├── Jtw24.h │ │ ├── Jtw26.cpp │ │ └── Jtw26.h │ ├── cwCcw │ │ ├── CwCcw.cpp │ │ └── CwCcw.h │ ├── ktech │ │ ├── KTech.cpp │ │ └── KTech.h │ ├── pulseDir │ │ ├── PulseDir.cpp │ │ └── PulseDir.h │ ├── pulseOnly │ │ ├── PulseOnly.cpp │ │ └── PulseOnly.h │ ├── quadrature │ │ ├── Quadrature.cpp │ │ └── Quadrature.h │ ├── quadratureEsp32 │ │ ├── QuadratureEsp32.cpp │ │ └── QuadratureEsp32.h │ ├── serialBridge │ │ ├── SerialBridge.cpp │ │ └── SerialBridge.h │ └── virtualEnc │ │ ├── VirtualEnc.cpp │ │ └── VirtualEnc.h ├── ethernet │ ├── EthernetManager.cpp │ ├── EthernetManager.defaults.h │ ├── EthernetManager.h │ ├── cmdServer │ │ ├── CmdServer.cpp │ │ └── CmdServer.h │ └── webServer │ │ ├── WebServer.cpp │ │ └── WebServer.h ├── gpioEx │ ├── GpioBase.cpp │ ├── GpioBase.h │ ├── GpioEx.h │ ├── ds2413 │ │ ├── Ds2413.cpp │ │ └── Ds2413.h │ ├── mcp23008 │ │ ├── Mcp23008.cpp │ │ └── Mcp23008.h │ ├── mcp23017 │ │ ├── Mcp23017.cpp │ │ └── Mcp23017.h │ ├── pcf8574 │ │ ├── Pcf8574.cpp │ │ └── Pcf8574.h │ ├── pcf8575 │ │ ├── Pcf8575.cpp │ │ └── Pcf8575.h │ ├── ssr74HC595 │ │ ├── Ssr74HC595.cpp │ │ └── Ssr74HC595.h │ ├── sws │ │ ├── Sws.cpp │ │ └── Sws.h │ └── tca9555 │ │ ├── Tca9555.cpp │ │ └── Tca9555.h ├── nv │ ├── 24xx │ │ ├── 24XX.cpp │ │ └── 24XX.h │ ├── Nv.h │ ├── NvBase.cpp │ ├── NvBase.h │ ├── eeprom │ │ ├── EEPROM.cpp │ │ └── EEPROM.h │ ├── esp │ │ ├── Esp.cpp │ │ └── Esp.h │ ├── m0 │ │ ├── M0.cpp │ │ └── M0.h │ └── mb85rc │ │ ├── MB85RC.cpp │ │ └── MB85RC.h ├── pushButton │ ├── PushButton.cpp │ └── PushButton.h ├── sense │ ├── Sense.cpp │ └── Sense.h ├── serial │ ├── Serial_IP_Ethernet.cpp │ ├── Serial_IP_Ethernet.h │ ├── Serial_IP_Ethernet_Client.cpp │ ├── Serial_IP_Ethernet_Client.h │ ├── Serial_IP_Wifi.cpp │ ├── Serial_IP_Wifi.h │ ├── Serial_IP_Wifi_Client.cpp │ ├── Serial_IP_Wifi_Client.h │ ├── Serial_Local.cpp │ ├── Serial_Local.h │ ├── Serial_MEGA2560.cpp │ ├── Serial_MEGA2560.h │ ├── Serial_ST4_Master.cpp │ ├── Serial_ST4_Master.h │ ├── Serial_ST4_Slave.cpp │ └── Serial_ST4_Slave.h ├── softSpi │ ├── Pins.h │ ├── SoftSpi.cpp │ └── SoftSpi.h ├── sound │ ├── Sound.cpp │ └── Sound.h ├── tasks │ ├── HAL_ATMEGA328_HWTIMER.h │ ├── HAL_EMPTY_HWTIMER.h │ ├── HAL_ESP32_HWTIMER.h │ ├── HAL_ESP32_V3_HWTIMER.h │ ├── HAL_HWTIMERS.h │ ├── HAL_MEGA2560_HWTIMER.h │ ├── HAL_PROFILER.h │ ├── HAL_STM32_HWTIMER.h │ ├── HAL_TEENSY_HWTIMER.h │ ├── OnTask.cpp │ ├── OnTask.h │ └── OnTaskExample.ino.txt ├── tls │ ├── PPS.cpp │ ├── PPS.h │ ├── Tls.h │ ├── TlsBase.cpp │ ├── TlsBase.h │ ├── ds3231 │ │ ├── DS3231.cpp │ │ └── DS3231.h │ ├── ds3234 │ │ ├── DS3234.cpp │ │ └── DS3234.h │ ├── gps │ │ ├── GPS.cpp │ │ └── GPS.h │ ├── ntp │ │ ├── NTP.cpp │ │ └── NTP.h │ ├── sd3031 │ │ ├── SD3031.cpp │ │ └── SD3031.h │ └── teensy │ │ ├── Teensy.cpp │ │ └── Teensy.h ├── watchdog │ ├── Watchdog.cpp │ └── Watchdog.h └── wifi │ ├── WifiManager.cpp │ ├── WifiManager.defaults.h │ ├── WifiManager.h │ ├── cmdServer │ ├── CmdServer.cpp │ └── CmdServer.h │ └── webServer │ ├── WebServer.cpp │ └── WebServer.h ├── libApp ├── bleGamepad │ ├── BleConfig.h │ ├── BleGamepad.cpp │ └── BleGamepad.h ├── cmd │ ├── Cmd.cpp │ └── Cmd.h ├── encoders │ ├── Encoders.cpp │ └── Encoders.h ├── misc │ ├── Misc.cpp │ └── Misc.h └── status │ ├── State.cpp │ ├── State.h │ ├── StateAuxiliary.cpp │ ├── StateController.cpp │ ├── StateEncoders.cpp │ ├── StateFocuser.cpp │ ├── StateMount.cpp │ ├── StateRotator.cpp │ ├── Status.cpp │ ├── Status.h │ ├── Version.cpp │ └── Version.h ├── locales ├── Locale.h ├── Locales.h ├── Strings_cn.h ├── Strings_de.h ├── Strings_en.h └── Strings_es.h ├── pages ├── Err404.cpp ├── KeyValue.cpp ├── KeyValue.h ├── LibraryHelp.cpp ├── LibraryHelp.h ├── Page.cpp ├── Page.h ├── Pages.common.h ├── Pages.h ├── auxiliary │ ├── Auxiliary.cpp │ └── Auxiliary.h ├── encoders │ ├── AxisTile.cpp │ ├── AxisTile.h │ ├── Encoders.cpp │ ├── Encoders.h │ ├── SyncTile.cpp │ └── SyncTile.h ├── focuser │ ├── BacklashTcfTile.cpp │ ├── BacklashTcfTile.h │ ├── Focuser.cpp │ ├── Focuser.h │ ├── HomeTile.cpp │ ├── HomeTile.h │ ├── SelectTile.cpp │ ├── SelectTile.h │ ├── SlewingTile.cpp │ └── SlewingTile.h ├── htmlHeaders.h ├── htmlMessages.h ├── htmlScripts.h ├── index │ ├── AmbientTile.cpp │ ├── AmbientTile.h │ ├── AxisTile.cpp │ ├── AxisTile.h │ ├── Index.cpp │ ├── Index.h │ ├── ServoCalibrateTile.cpp │ ├── ServoCalibrateTile.h │ ├── ServoTile.cpp │ ├── ServoTile.h │ ├── StatusTile.cpp │ └── StatusTile.h ├── mount │ ├── AlignTile.cpp │ ├── AlignTile.h │ ├── GotoTile.cpp │ ├── GotoTile.h │ ├── GuideTile.cpp │ ├── GuideTile.h │ ├── HomeParkTile.cpp │ ├── HomeParkTile.h │ ├── LibraryTile.cpp │ ├── LibraryTile.h │ ├── LimitsTile.cpp │ ├── LimitsTile.h │ ├── Mount.cpp │ ├── Mount.h │ ├── PecTile.cpp │ ├── PecTile.h │ ├── SiteTile.cpp │ ├── SiteTile.h │ ├── TrackingTile.cpp │ └── TrackingTile.h ├── network │ ├── Network.cpp │ └── Network.h └── rotator │ ├── BacklashTile.cpp │ ├── BacklashTile.h │ ├── DeRotatorTile.cpp │ ├── DeRotatorTile.h │ ├── HomeTile.cpp │ ├── HomeTile.h │ ├── Rotator.cpp │ ├── Rotator.h │ ├── SlewingTile.cpp │ └── SlewingTile.h └── pinmaps ├── Models.h ├── Pins.Esp32.h ├── Pins.Esp32c3.h ├── Pins.Esp32s2.h ├── Pins.Esp8266.h ├── Pins.M0.h ├── Pins.Teensy.h ├── Pins.defaults.h └── pinmaps.ino /.gitignore: -------------------------------------------------------------------------------- 1 | 2 | *.json 3 | esp32.svd 4 | debug.cfg 5 | debug.svd 6 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # OnStep Smart Web Server 2 | This is the WiFi and Ethernet web server for OnStep, it is also sometimes referred to as the "SWS". 3 | The SWS enables OnStep to be controlled from a website and/or by passing commands over IP. 4 | The SWS is known to work from personal computers (using a web browser, ASCOM, or INDI), phones (Android and iOS), tablets, and the wireless Smart Hand Controller. 5 | 6 | # Optionally, the SWS can also provide: 7 | Support for encoders where it integrates tightly with OnStep; or if not using Encoders, OnStepX can use those four connections (pins) as general purpose I/O. 8 | There is also support for using the "ACGAM R1 Bluetooth 4.0 Wireless Gamepad" over Bluetooth LE which you can read about here: 9 | https://onstep.groups.io/g/main/wiki/26762 10 | 11 | # Flashing The Smart Web Server 12 | The exact flashing procedure depends on which device you will be using. You can find instructions for setting up the SWS in its Wiki here: 13 | https://onstep.groups.io/g/main/wiki/26881 14 | 15 | # License 16 | The Smart Web Server is open source free software, licensed under the GPL. 17 | 18 | See [LICENSE.txt](./LICENSE.txt) file. 19 | 20 | # Primary Author 21 | [Howard Dutton](http://www.stellarjourney.com) 22 | -------------------------------------------------------------------------------- /src/Common.h: -------------------------------------------------------------------------------- 1 | // Common includes 2 | #pragma once 3 | 4 | // enable lib support for the command and web servers 5 | #define WEB_SERVER ON 6 | 7 | #include 8 | 9 | #include "lib/Macros.h" 10 | #include "lib/Constants.h" 11 | 12 | #include "Constants.h" 13 | #include "../Config.h" 14 | #include "Config.defaults.h" 15 | #include "HAL/HAL.h" 16 | #include "lib/debug/Debug.h" 17 | 18 | #include "pinmaps/Models.h" 19 | 20 | #include "libApp/status/Version.h" 21 | #include "libApp/status/State.h" 22 | -------------------------------------------------------------------------------- /src/Constants.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Constants 3 | #pragma once 4 | 5 | // misc. 6 | #define PROD_ABV "SWS" 7 | 8 | #define METRIC ON 9 | #define IMPERIAL -200 10 | #define LOCALE_DEFAULT -201 11 | #define AUTO_ON -202 12 | #define AUTO_OFF -203 13 | #define FWU -204 14 | 15 | // ajax page update feature 16 | #define AJAX_PAGE_UPDATE_RATE_FAST_MS 500 // fast update rate 17 | #define AJAX_PAGE_UPDATE_FAST_SHED_MS 5000 // time before return to normal update rate 18 | #define AJAX_PAGE_LAZY_GET_MS 1000 // wait time for lazy get 19 | 20 | // various auxillary features 21 | #define SWITCH 1 22 | #define ANALOG_OUTPUT 2 23 | #define DEW_HEATER 3 24 | #define INTERVALOMETER 4 25 | 26 | // The settings below are for initialization only, afterward they are stored and recalled from EEPROM and must 27 | // be changed in the web interface OR with a reset (for initialization again) as described in the Config.h comments 28 | #define TIMEOUT_WEB 200 29 | #define TIMEOUT_CMD 200 30 | 31 | // task manager 32 | #define TASKS_MAX 32 // up to 32 tasks 33 | #define TASKS_SKIP_MISSED 34 | 35 | // EEPROM contents 36 | #define INIT_NV_KEY 698623877UL 37 | 38 | #define NV_TIMEOUT_CMD 5 // 2 bytes 39 | #define NV_TIMEOUT_WEB 7 // 2 bytes 40 | #define NV_ETHERNET_SETTINGS_BASE 100 // up to 150 bytes (108) 41 | #define NV_WIFI_SETTINGS_BASE 250 // up to 500 bytes (258) 42 | #define NV_ENCODER_SETTINGS_BASE 750 // up to 75 bytes (72) 43 | 44 | 45 | -------------------------------------------------------------------------------- /src/HAL/default/Default.h: -------------------------------------------------------------------------------- 1 | // Platform setup ------------------------------------------------------------------------------------ 2 | #pragma once 3 | 4 | // We define a more generic symbol, in case more Platform_Name boards based on different lines are supported 5 | 6 | // Base rate for critical task timing 7 | #define HAL_FRACTIONAL_SEC 100.0F 8 | 9 | // Analog read and write 10 | #ifndef HAL_VCC 11 | #define HAL_VCC 3.3F 12 | #endif 13 | #ifndef ANALOG_READ_RANGE 14 | #define ANALOG_READ_RANGE 1023 15 | #else 16 | #error "Configuration (Config.h): ANALOG_READ_RANGE can't be changed on this platform" 17 | #endif 18 | #ifndef ANALOG_WRITE_RANGE 19 | #define ANALOG_WRITE_RANGE 255 20 | #else 21 | #error "Configuration (Config.h): ANALOG_WRITE_RANGE can't be changed on this platform" 22 | #endif 23 | 24 | // Lower limit (fastest) step rate in uS for this platform (in SQW mode) and width of step pulse 25 | #ifndef HAL_MAXRATE_LOWER_LIMIT 26 | #define HAL_MAXRATE_LOWER_LIMIT 60 27 | #endif 28 | #ifndef HAL_PULSE_WIDTH 29 | #define HAL_PULSE_WIDTH 10000 // in ns, estimated 30 | #endif 31 | 32 | // New symbol for the default I2C port ------------------------------------------------------------- 33 | #include 34 | #ifndef HAL_WIRE 35 | #define HAL_WIRE Wire 36 | #endif 37 | #ifndef HAL_WIRE_CLOCK 38 | #define HAL_WIRE_CLOCK 100000 39 | #endif 40 | 41 | // Non-volatile storage ---------------------------------------------------------------------------- 42 | #if NV_DRIVER == NV_DEFAULT 43 | #undef NV_DRIVER 44 | #define NV_DRIVER NV_EEPROM 45 | #endif 46 | 47 | //-------------------------------------------------------------------------------------------------- 48 | // Internal MCU temperature (in degrees C) 49 | #define HAL_TEMP() ( NAN ) 50 | 51 | //-------------------------------------------------------------------------------------------------- 52 | // General purpose initialize for HAL 53 | #define HAL_INIT() { ; } 54 | 55 | //--------------------------------------------------------------------------------------------------- 56 | // Misc. includes to support this processor's operation 57 | 58 | // stand-in for delayNanoseconds() 59 | #define delayNanoseconds(ns) delayMicroseconds(ceilf(ns/1000.0F)) 60 | -------------------------------------------------------------------------------- /src/HAL/esp/ESP32UnoR4WiFi.h: -------------------------------------------------------------------------------- 1 | // Platform setup ------------------------------------------------------------------------------------ 2 | #pragma once 3 | 4 | // This is for fast processors with hardware FP 5 | #define HAL_FAST_PROCESSOR 6 | 7 | // Base rate for critical task timing (0.0095s = 0.14", 0.2 sec/day) 8 | #define HAL_FRACTIONAL_SEC 105.2631579F 9 | 10 | // Analog read and write 11 | #ifndef HAL_VCC 12 | #define HAL_VCC 3.3F 13 | #endif 14 | #ifndef ANALOG_READ_RANGE 15 | #define ANALOG_READ_RANGE 1023 16 | #endif 17 | #ifndef ANALOG_WRITE_RANGE 18 | #define ANALOG_WRITE_RANGE 255 19 | #endif 20 | 21 | // Lower limit (fastest) step rate in us for this platform (in SQW mode) and width of step pulse 22 | #define HAL_MAXRATE_LOWER_LIMIT 60 23 | #define HAL_PULSE_WIDTH 10000 // in ns, estimated 24 | 25 | // New symbol for the default I2C port ------------------------------------------------------------- 26 | #include 27 | #ifndef HAL_WIRE 28 | #define HAL_WIRE Wire 29 | #endif 30 | #ifndef HAL_WIRE_CLOCK 31 | #define HAL_WIRE_CLOCK 100000 32 | #endif 33 | 34 | // Non-volatile storage ---------------------------------------------------------------------------- 35 | #if NV_DRIVER == NV_DEFAULT 36 | #define E2END 2047 37 | #undef NV_DRIVER 38 | #define NV_DRIVER NV_EEPROM 39 | #endif 40 | 41 | //-------------------------------------------------------------------------------------------------- 42 | // Internal MCU temperature (in degrees C) 43 | #define HAL_TEMP() ( NAN ) 44 | 45 | //-------------------------------------------------------------------------------------------------- 46 | // General purpose initialize for HAL 47 | #define HAL_INIT() { ; } 48 | 49 | // stand-in for delayNanoseconds() 50 | #define delayNanoseconds(ns) delayMicroseconds(ceilf(ns/1000.0F)) 51 | -------------------------------------------------------------------------------- /src/HAL/esp/ESP8266.h: -------------------------------------------------------------------------------- 1 | // Platform setup ------------------------------------------------------------------------------------ 2 | #pragma once 3 | 4 | // We define a more generic symbol, in case more Platform_Name boards based on different lines are supported 5 | 6 | // Base rate for critical task timing 7 | #define HAL_FRACTIONAL_SEC 100.0F 8 | 9 | // Analog read and write 10 | #ifndef HAL_VCC 11 | #define HAL_VCC 3.3F 12 | #endif 13 | #ifndef ANALOG_READ_RANGE 14 | #define ANALOG_READ_RANGE 1023 15 | #endif 16 | #ifndef ANALOG_WRITE_RANGE 17 | #define ANALOG_WRITE_RANGE 255 18 | #endif 19 | 20 | // Lower limit (fastest) step rate in us for this platform (in SQW mode) and width of step pulse 21 | #define HAL_MAXRATE_LOWER_LIMIT 60 22 | #define HAL_PULSE_WIDTH 10000 // in ns, estimated 23 | 24 | // New symbol for the default I2C port --------------------------------------------------------------- 25 | #include 26 | #ifndef HAL_WIRE 27 | #define HAL_WIRE Wire 28 | #endif 29 | #ifndef HAL_WIRE_CLOCK 30 | #define HAL_WIRE_CLOCK 100000 31 | #endif 32 | 33 | // Non-volatile storage ------------------------------------------------------------------------------ 34 | #if NV_DRIVER == NV_DEFAULT 35 | #define E2END 1023 36 | #undef NV_DRIVER 37 | #define NV_DRIVER NV_ESP 38 | #endif 39 | 40 | //-------------------------------------------------------------------------------------------------- 41 | // Internal MCU temperature (in degrees C) 42 | #define HAL_TEMP() ( NAN ) 43 | 44 | //-------------------------------------------------------------------------------------------------- 45 | // General purpose initialize for HAL 46 | #define HAL_INIT() { analogWriteRange((int)log2(ANALOG_WRITE_RANGE + 1)); } 47 | 48 | //----------------------------------------------------------------------------------------------------- 49 | // Misc. includes and defines to support this processor's operation 50 | 51 | // MCU reset 52 | #define HAL_RESET() ESP.restart() 53 | 54 | // stand-in for delayNanoseconds(), assumes 80MHz clock 55 | #define delayNanoseconds(ns) { unsigned int c = ESP.getCycleCount() + ns/12.5F; do {} while ((int)(ESP.getCycleCount() - c) < 0); } 56 | -------------------------------------------------------------------------------- /src/HAL/mbed/Rpi2040.h: -------------------------------------------------------------------------------- 1 | // Platform setup ------------------------------------------------------------------------------------ 2 | #pragma once 3 | 4 | // 1/100 second resolution 5 | #define HAL_FRACTIONAL_SEC 100.0F 6 | 7 | // This platform has 8 bit PWM 8 | #ifndef HAL_VCC 9 | #define HAL_VCC 3.3F 10 | #endif 11 | #ifndef ANALOG_READ_RANGE 12 | #define ANALOG_READ_RANGE 1023 // always use 2^n - 1, within the platform's limits 13 | #else 14 | #error "Configuration (Config.h): ANALOG_READ_RANGE can't be changed on this platform" 15 | #endif 16 | #ifndef ANALOG_WRITE_RANGE 17 | #define ANALOG_WRITE_RANGE 255 // always use 2^n - 1, within the platform's limits 18 | #else 19 | #error "Configuration (Config.h): ANALOG_WRITE_RANGE can't be changed on this platform" 20 | #endif 21 | 22 | // Lower limit (fastest) step rate in us for this platform (in SQW mode) and width of step pulse 23 | #define HAL_MAXRATE_LOWER_LIMIT 76.8 24 | #define HAL_PULSE_WIDTH 10000 // in ns, estimated 25 | 26 | // New symbol for the default I2C port ------------------------------------------------------------- 27 | #include 28 | #ifndef HAL_WIRE 29 | #define HAL_WIRE Wire 30 | #endif 31 | #ifndef HAL_WIRE_CLOCK 32 | #define HAL_WIRE_CLOCK 100000 33 | #endif 34 | 35 | // Non-volatile storage ---------------------------------------------------------------------------- 36 | #if NV_DRIVER == NV_DEFAULT 37 | #undef NV_DRIVER 38 | #define NV_DRIVER NV_AT24C32 39 | #endif 40 | 41 | //-------------------------------------------------------------------------------------------------- 42 | // Internal MCU temperature (in degrees C) 43 | #define HAL_TEMP() ( NAN ) 44 | 45 | //-------------------------------------------------------------------------------------------------- 46 | // General purpose initialize for HAL 47 | 48 | #define HAL_INIT() { \ 49 | } 50 | 51 | // MCU reset 52 | #define HAL_RESET() (*((volatile uint32_t*)(PPB_BASE + 0x0ED0C))) = 0x5FA0004; 53 | 54 | //--------------------------------------------------------------------------------------------------- 55 | // Misc. includes to support this processor's operation 56 | 57 | // stand-in for delayNanoseconds() 58 | #define delayNanoseconds(ns) delayMicroseconds(ceilf(ns/1000.0F)) 59 | -------------------------------------------------------------------------------- /src/HAL/mbed/Rpi2350.h: -------------------------------------------------------------------------------- 1 | // Platform setup ------------------------------------------------------------------------------------ 2 | #pragma once 3 | 4 | // 1/100 second resolution 5 | #define HAL_FRACTIONAL_SEC 100.0F 6 | 7 | // This platform has 8 bit PWM 8 | #ifndef HAL_VCC 9 | #define HAL_VCC 3.3F 10 | #endif 11 | #ifndef ANALOG_READ_RANGE 12 | #define ANALOG_READ_RANGE 1023 // always use 2^n - 1, within the platform's limits 13 | #else 14 | #error "Configuration (Config.h): ANALOG_READ_RANGE can't be changed on this platform" 15 | #endif 16 | #ifndef ANALOG_WRITE_RANGE 17 | #define ANALOG_WRITE_RANGE 255 // always use 2^n - 1, within the platform's limits 18 | #else 19 | #error "Configuration (Config.h): ANALOG_WRITE_RANGE can't be changed on this platform" 20 | #endif 21 | 22 | // Lower limit (fastest) step rate in us for this platform (in SQW mode) and width of step pulse 23 | #define HAL_MAXRATE_LOWER_LIMIT 76.8 24 | #define HAL_PULSE_WIDTH 10000 // in ns, estimated 25 | 26 | // New symbol for the default I2C port ------------------------------------------------------------- 27 | #include 28 | #ifndef HAL_WIRE 29 | #define HAL_WIRE Wire 30 | #endif 31 | #ifndef HAL_WIRE_CLOCK 32 | #define HAL_WIRE_CLOCK 100000 33 | #endif 34 | 35 | // Non-volatile storage ---------------------------------------------------------------------------- 36 | #if NV_DRIVER == NV_DEFAULT 37 | #undef NV_DRIVER 38 | #define NV_DRIVER NV_AT24C32 39 | #endif 40 | 41 | //-------------------------------------------------------------------------------------------------- 42 | // Internal MCU temperature (in degrees C) 43 | #define HAL_TEMP() ( NAN ) 44 | 45 | //-------------------------------------------------------------------------------------------------- 46 | // General purpose initialize for HAL 47 | 48 | #define HAL_INIT() { \ 49 | } 50 | 51 | // MCU reset 52 | #define HAL_RESET() (*((volatile uint32_t*)(PPB_BASE + 0x0ED0C))) = 0x5FA0004; 53 | 54 | //--------------------------------------------------------------------------------------------------- 55 | // Misc. includes to support this processor's operation 56 | 57 | // stand-in for delayNanoseconds() 58 | #define delayNanoseconds(ns) delayMicroseconds(ceilf(ns/1000.0F)) 59 | -------------------------------------------------------------------------------- /src/Validate.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #if DISPLAY_RESET_CONTROLS == FWU 4 | #if SERIAL_SWAP != OFF 5 | #error "Configuration (Config.h): Setting DISPLAY_RESET_CONTROLS FWU must be used with SERIAL_SWAP OFF only" 6 | #endif 7 | #endif 8 | 9 | #if ESP32 10 | #if (AP_ENABLED == true && STA_ENABLED == true) 11 | #error "AP and Station modes cannot be enabled at the same time with ESP32." 12 | #endif 13 | #endif 14 | -------------------------------------------------------------------------------- /src/lib/1wire/1Wire.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Dallas/Maxim 1-Wire library 3 | 4 | #include "1Wire.h" 5 | 6 | #if defined(DS1820_DEVICES_PRESENT) || (defined(GPIO_DEVICE) && GPIO_DEVICE == DS2413) 7 | 8 | OneWire oneWire(ONE_WIRE_PIN); 9 | 10 | #endif -------------------------------------------------------------------------------- /src/lib/1wire/1Wire.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Dallas/Maxim 1-Wire library 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #if defined(DS1820_DEVICES_PRESENT) || (defined(GPIO_DEVICE) && GPIO_DEVICE == DS2413) 8 | 9 | #include // my OneWire library https://github.com/hjd1964/OneWire 10 | 11 | extern OneWire oneWire; 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /src/lib/analog/AN_ESP32.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Arduino compatible analogWrite() and tone() functions for the ESP32 3 | #pragma once 4 | 5 | #include "Arduino.h" 6 | #include "../../Common.h" 7 | 8 | #if defined(ESP32) 9 | #if ESP_ARDUINO_VERSION < 0x20000 + 3 10 | // starts tone on the specified pin of frequency (Hz) for the duration (in ms) 11 | extern void tone(uint8_t pin, unsigned int frequency, unsigned long duration = 0); 12 | // stops tone on the specified pin 13 | extern void noTone(uint8_t pin); 14 | 15 | // analog pwm of value (default 8 bit) on the specified pin 16 | extern void analogWrite(uint8_t pin, int value); 17 | // analog pwm resolution (8 to 16 bit) 18 | extern void analogWriteResolution(int value); 19 | // analog pwm frequency (500 to 10000Hz) 20 | extern void analogWriteFrequency(int value); 21 | #endif 22 | #endif 23 | -------------------------------------------------------------------------------- /src/lib/axis/motor/Drivers.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | typedef struct DriverOutputStatus { 4 | bool shortToGround; 5 | bool openLoad; 6 | } DriverOutputStatus; 7 | 8 | typedef struct DriverStatus { 9 | bool active; 10 | DriverOutputStatus outputA; 11 | DriverOutputStatus outputB; 12 | bool overTemperatureWarning; 13 | bool overTemperature; 14 | bool standstill; 15 | bool fault; 16 | } DriverStatus; 17 | -------------------------------------------------------------------------------- /src/lib/axis/motor/oDrive/ODrive.ino: -------------------------------------------------------------------------------- 1 | // Placeholder file 2 | // Nothing to see here ... 3 | // 4 | // This file is only present so the Arduino IDE can edit the .h file(s) 5 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/Servo.ino: -------------------------------------------------------------------------------- 1 | // Placeholder file 2 | // Nothing to see here ... 3 | // 4 | // This file is only present so the Arduino IDE can edit the .h file(s) 5 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/dc/Dc.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // axis servo DC motor driver 3 | #pragma once 4 | 5 | #include 6 | #include "../../../../../Common.h" 7 | 8 | #ifdef SERVO_DC_PRESENT 9 | 10 | #include "../ServoDriver.h" 11 | 12 | typedef struct ServoDcPins { 13 | int16_t in1; 14 | uint8_t inState1; 15 | int16_t in2; 16 | uint8_t inState2; 17 | int16_t enable; 18 | uint8_t enabledState; 19 | int16_t fault; 20 | } ServoDcPins; 21 | 22 | typedef struct ServoDcSettings { 23 | int16_t model; 24 | int8_t status; 25 | int32_t velocityMax; // in % of max power 26 | int32_t acceleration; // in %/second/second 27 | } ServoDcSettings; 28 | 29 | class ServoDc : public ServoDriver { 30 | public: 31 | // constructor 32 | ServoDc(uint8_t axisNumber, const ServoDcPins *Pins, const ServoDcSettings *Settings); 33 | 34 | // decodes driver model and sets up the pin modes 35 | bool init(); 36 | 37 | // enable or disable the driver using the enable pin or other method 38 | void enable(bool state); 39 | 40 | // set motor velocity by adjusting power (0 to SERVO_ANALOG_WRITE_RANGE for 0 to 100% power) 41 | float setMotorVelocity(float power); 42 | 43 | // update status info. for driver 44 | void updateStatus(); 45 | 46 | const ServoDcSettings *Settings; 47 | 48 | private: 49 | // motor control update 50 | void pwmUpdate(float power); 51 | 52 | const ServoDcPins *Pins; 53 | 54 | float currentVelocity = 0.0F; 55 | float acceleration; 56 | float accelerationFs; 57 | }; 58 | 59 | #endif 60 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/dcTmcSPI/DcTmcSPI.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // axis servo TMC2130 and TMC5160 DC motor driver 3 | #pragma once 4 | 5 | #include 6 | #include "../../../../../Common.h" 7 | 8 | #ifdef SERVO_DC_TMC_SPI_PRESENT 9 | 10 | #include "../ServoDriver.h" 11 | 12 | #ifndef DRIVER_TMC_STEPPER_AUTOGRAD 13 | #define DRIVER_TMC_STEPPER_AUTOGRAD true 14 | #endif 15 | 16 | #include // https://github.com/teemuatlut/TMCStepper 17 | 18 | typedef struct ServoDcTmcSpiPins { 19 | int16_t step; 20 | int16_t dir; 21 | int16_t enable; 22 | uint8_t enabledState; 23 | int16_t m0; 24 | int16_t m1; 25 | int16_t m2; 26 | int16_t m3; 27 | int16_t fault; 28 | } ServoDcTmcPins; 29 | 30 | typedef struct ServoDcTmcSettings { 31 | int16_t model; 32 | int8_t status; 33 | int32_t velocityMax; // maximum velocity in steps/second 34 | int32_t acceleration; // acceleration steps/second/second 35 | int16_t microsteps; 36 | int16_t current; 37 | } ServoDcTmcSettings; 38 | 39 | class ServoDcTmcSPI : public ServoDriver { 40 | public: 41 | // constructor 42 | ServoDcTmcSPI(uint8_t axisNumber, const ServoDcTmcPins *Pins, const ServoDcTmcSettings *TmcSettings); 43 | 44 | // decodes driver model and sets up the pin modes 45 | bool init(); 46 | 47 | // enable or disable the driver using the enable pin or other method 48 | void enable(bool state); 49 | 50 | // power level to the motor 51 | float setMotorVelocity(float power); 52 | 53 | const ServoDcTmcSettings *Settings; 54 | 55 | private: 56 | // read status info. from driver 57 | void readStatus(); 58 | 59 | TMCStepper *driver; 60 | 61 | bool powered = false; 62 | float currentVelocity = 0.0F; 63 | float acceleration; 64 | float accelerationFs; 65 | const ServoDcTmcSpiPins *Pins; 66 | }; 67 | 68 | #endif 69 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/feedback/Feedback.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // servo motor feedback 3 | #pragma once 4 | 5 | #include "Pid/Pid.h" 6 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/feedback/FeedbackBase.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // servo motor feedback 3 | 4 | #include "FeedbackBase.h" 5 | 6 | #ifdef SERVO_MOTOR_PRESENT 7 | 8 | // initialize feedback control and parameters 9 | void Feedback::init(uint8_t axisNumber, ServoControl *control, float controlRange) { 10 | this->axisNumber = axisNumber; 11 | 12 | this->control = control; 13 | control->in = 0; 14 | control->set = 0; 15 | } 16 | 17 | // get default feedback parameters 18 | void Feedback::getDefaultParameters(float *param1, float *param2, float *param3, float *param4, float *param5, float *param6) { 19 | *param1 = default_param1; 20 | *param2 = default_param2; 21 | *param3 = default_param3; 22 | *param4 = default_param4; 23 | *param5 = default_param5; 24 | *param6 = default_param6; 25 | } 26 | 27 | // set default feedback parameters 28 | void Feedback::setDefaultParameters(float param1, float param2, float param3, float param4, float param5, float param6) { 29 | default_param1 = param1; 30 | default_param2 = param2; 31 | default_param3 = param3; 32 | default_param4 = param4; 33 | default_param5 = param5; 34 | default_param6 = param6; 35 | setParameters(param1, param2, param3, param4, param5, param6); 36 | } 37 | 38 | // set feedback parameters 39 | void Feedback::setParameters(float param1, float param2, float param3, float param4, float param5, float param6) { 40 | this->param1 = param1; 41 | this->param2 = param2; 42 | this->param3 = param3; 43 | this->param4 = param4; 44 | this->param5 = param5; 45 | this->param6 = param6; 46 | } 47 | 48 | // validate driver parameters 49 | bool Feedback::validateParameters(float param1, float param2, float param3, float param4, float param5, float param6) { 50 | return true; 51 | } 52 | 53 | #endif -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Filter.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // servo filter 3 | #pragma once 4 | 5 | #include "Kalman/Kalman.h" 6 | #include "Learning/Learning.h" 7 | #include "Rolling/Rolling.h" 8 | #include "Windowing/Windowing.h" 9 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/FilterBase.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // servo filter 3 | 4 | #include "FilterBase.h" 5 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/FilterBase.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // servo filter 3 | #pragma once 4 | 5 | #include "../../../../../Common.h" 6 | 7 | #ifndef AXIS1_SERVO_FLTR 8 | #define AXIS1_SERVO_FLTR OFF 9 | #endif 10 | #ifndef AXIS2_SERVO_FLTR 11 | #define AXIS2_SERVO_FLTR OFF 12 | #endif 13 | #ifndef AXIS3_SERVO_FLTR 14 | #define AXIS3_SERVO_FLTR OFF 15 | #endif 16 | #ifndef AXIS4_SERVO_FLTR 17 | #define AXIS4_SERVO_FLTR OFF 18 | #endif 19 | #ifndef AXIS5_SERVO_FLTR 20 | #define AXIS5_SERVO_FLTR OFF 21 | #endif 22 | #ifndef AXIS6_SERVO_FLTR 23 | #define AXIS6_SERVO_FLTR OFF 24 | #endif 25 | #ifndef AXIS7_SERVO_FLTR 26 | #define AXIS7_SERVO_FLTR OFF 27 | #endif 28 | #ifndef AXIS8_SERVO_FLTR 29 | #define AXIS8_SERVO_FLTR OFF 30 | #endif 31 | #ifndef AXIS9_SERVO_FLTR 32 | #define AXIS9_SERVO_FLTR OFF 33 | #endif 34 | 35 | class Filter { 36 | public: 37 | virtual long update(long encoderCounts, long motorCounts, bool isTracking) { UNUSED(motorCounts); UNUSED(isTracking); return encoderCounts; } 38 | 39 | private: 40 | bool initialized = false; 41 | }; 42 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Kalman/Kalman.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // kalman filter 3 | 4 | #include "Kalman.h" 5 | 6 | #if AXIS1_SERVO_FLTR == KALMAN || AXIS2_SERVO_FLTR == KALMAN || AXIS3_SERVO_FLTR == KALMAN || \ 7 | AXIS4_SERVO_FLTR == KALMAN || AXIS5_SERVO_FLTR == KALMAN || AXIS6_SERVO_FLTR == KALMAN || \ 8 | AXIS7_SERVO_FLTR == KALMAN || AXIS8_SERVO_FLTR == KALMAN || AXIS9_SERVO_FLTR == KALMAN 9 | 10 | KalmanFilter::KalmanFilter(float measurementUncertainty, float variance) { 11 | kalmanFilter = new SimpleKalmanFilter(measurementUncertainty, measurementUncertainty, variance); 12 | } 13 | 14 | long KalmanFilter::update(long encoderCounts, long motorCounts, bool isTracking) { 15 | UNUSED(isTracking); 16 | 17 | long delta = encoderCounts - motorCounts; 18 | 19 | if (!initialized) { 20 | result = encoderCounts - motorCounts; 21 | initialized = true; 22 | } else { 23 | result = kalmanFilter->updateEstimate(delta); 24 | } 25 | 26 | return result + motorCounts; 27 | } 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Kalman/Kalman.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // kalman filter 3 | #pragma once 4 | 5 | #include "../FilterBase.h" 6 | 7 | #if AXIS1_SERVO_FLTR == KALMAN || AXIS2_SERVO_FLTR == KALMAN || AXIS3_SERVO_FLTR == KALMAN || \ 8 | AXIS4_SERVO_FLTR == KALMAN || AXIS5_SERVO_FLTR == KALMAN || AXIS6_SERVO_FLTR == KALMAN || \ 9 | AXIS7_SERVO_FLTR == KALMAN || AXIS8_SERVO_FLTR == KALMAN || AXIS9_SERVO_FLTR == KALMAN 10 | 11 | #include // https://github.com/denyssene/SimpleKalmanFilter 12 | 13 | class KalmanFilter : public Filter { 14 | public: 15 | KalmanFilter(float measurementUncertainty, float variance); 16 | 17 | long update(long encoderCounts, long motorCounts, bool isTracking); 18 | 19 | private: 20 | bool initialized = false; 21 | long long result; 22 | 23 | SimpleKalmanFilter *kalmanFilter; 24 | }; 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Learning/Learning.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // learning filter (experimental) 3 | #pragma once 4 | 5 | #include "../FilterBase.h" 6 | 7 | #if AXIS1_SERVO_FLTR == LEARNING 8 | 9 | class LearningFilter : public Filter { 10 | public: 11 | // windowSize: in counts for rolling average 12 | // frameWidth: in seconds for learning window 13 | // learn: true when the (high accuracy) motion critical to the process is stable 14 | LearningFilter(int windowSize, int frameWidth); 15 | 16 | long update(long encoderCounts, long motorCounts, bool learn); 17 | 18 | void analyze(); 19 | 20 | void reset(); 21 | 22 | private: 23 | bool active = false; 24 | bool initialized = false; 25 | bool lock = false; 26 | int windowSize; // in samples 27 | int frameWidth; // in samples 28 | 29 | float countsPerSecond; 30 | float countsPerSample; 31 | float samplesPerSecond; 32 | long phase = 0; 33 | long lastPhase = 0; 34 | long avgPhase = 0; 35 | long avgPhaseShift = 0; 36 | long correction = 0; 37 | float avgMaxDelta = 0; 38 | float avgMinDelta = 0; 39 | float avgAmplitude = 0; 40 | float avgPeriod = 0; // in samples 41 | long *deltas; 42 | long *counts; 43 | long index; 44 | long long avgDelta; 45 | long long avgEncoderCounts; 46 | long lastIndex = 0; 47 | }; 48 | 49 | extern LearningFilter filterAxis1; 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Rolling/Rolling.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // rolling average filter 3 | 4 | #include "Rolling.h" 5 | 6 | #if AXIS1_SERVO_FLTR == ROLLING || AXIS2_SERVO_FLTR == ROLLING || AXIS3_SERVO_FLTR == ROLLING || \ 7 | AXIS4_SERVO_FLTR == ROLLING || AXIS5_SERVO_FLTR == ROLLING || AXIS6_SERVO_FLTR == ROLLING || \ 8 | AXIS7_SERVO_FLTR == ROLLING || AXIS8_SERVO_FLTR == ROLLING || AXIS9_SERVO_FLTR == ROLLING 9 | 10 | RollingFilter::RollingFilter(int size) { 11 | this->size = size; 12 | } 13 | 14 | long RollingFilter::update(long encoderCounts, long motorCounts, bool isTracking) { 15 | UNUSED(isTracking); 16 | 17 | long delta = encoderCounts - motorCounts; 18 | 19 | if (!initialized) { 20 | result = encoderCounts - motorCounts; 21 | initialized = true; 22 | } 23 | 24 | result = (result*(size - 1) + delta)/size; 25 | return result + motorCounts; 26 | } 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Rolling/Rolling.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // rolling average filter 3 | #pragma once 4 | 5 | #include "../FilterBase.h" 6 | 7 | #if AXIS1_SERVO_FLTR == ROLLING || AXIS2_SERVO_FLTR == ROLLING || AXIS3_SERVO_FLTR == ROLLING || \ 8 | AXIS4_SERVO_FLTR == ROLLING || AXIS5_SERVO_FLTR == ROLLING || AXIS6_SERVO_FLTR == ROLLING || \ 9 | AXIS7_SERVO_FLTR == ROLLING || AXIS8_SERVO_FLTR == ROLLING || AXIS9_SERVO_FLTR == ROLLING 10 | 11 | class RollingFilter : public Filter { 12 | public: 13 | RollingFilter(int size); 14 | 15 | long update(long encoderCounts, long motorCounts, bool isTracking); 16 | 17 | private: 18 | bool initialized = false; 19 | int size; 20 | long long result; 21 | }; 22 | 23 | #endif 24 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Windowing/Windowing.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // windowing average filter 3 | 4 | #include "Windowing.h" 5 | 6 | #if AXIS1_SERVO_FLTR == WINDOWING || AXIS2_SERVO_FLTR == WINDOWING || AXIS3_SERVO_FLTR == WINDOWING || \ 7 | AXIS4_SERVO_FLTR == WINDOWING || AXIS5_SERVO_FLTR == WINDOWING || AXIS6_SERVO_FLTR == WINDOWING || \ 8 | AXIS7_SERVO_FLTR == WINDOWING || AXIS8_SERVO_FLTR == WINDOWING || AXIS9_SERVO_FLTR == WINDOWING 9 | 10 | WindowingFilter::WindowingFilter(int size) { 11 | this->size = size; 12 | values = new long[size]; 13 | } 14 | 15 | long WindowingFilter::update(long encoderCounts, long motorCounts, bool isTracking) { 16 | UNUSED(isTracking); 17 | 18 | long delta = encoderCounts - motorCounts; 19 | 20 | if (!initialized) { 21 | sum = delta*size; 22 | index = 0; 23 | for (int i = 0; i < size; i++) values[i] = delta; 24 | initialized = true; 25 | } 26 | 27 | sum -= values[index % size]; 28 | values[index % size] = delta; 29 | sum += delta; 30 | index++; 31 | 32 | return (sum/size) + motorCounts; 33 | } 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/filter/Windowing/Windowing.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // windowing average filter 3 | #pragma once 4 | 5 | #include "../FilterBase.h" 6 | 7 | #if AXIS1_SERVO_FLTR == WINDOWING || AXIS2_SERVO_FLTR == WINDOWING || AXIS3_SERVO_FLTR == WINDOWING || \ 8 | AXIS4_SERVO_FLTR == WINDOWING || AXIS5_SERVO_FLTR == WINDOWING || AXIS6_SERVO_FLTR == WINDOWING || \ 9 | AXIS7_SERVO_FLTR == WINDOWING || AXIS8_SERVO_FLTR == WINDOWING || AXIS9_SERVO_FLTR == WINDOWING 10 | 11 | class WindowingFilter : public Filter { 12 | public: 13 | WindowingFilter(int size); 14 | 15 | long update(long encoderCounts, long motorCounts, bool isTracking); 16 | 17 | private: 18 | bool initialized = false; 19 | int size; 20 | long *values; 21 | unsigned long index; 22 | long long sum; 23 | }; 24 | 25 | #endif -------------------------------------------------------------------------------- /src/lib/axis/motor/servo/kTech/KTech.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // axis servo KTech motor driver 3 | #pragma once 4 | 5 | #include 6 | #include "../../../../../Common.h" 7 | 8 | #ifdef SERVO_KTECH_PRESENT 9 | 10 | #include "../ServoDriver.h" 11 | 12 | #if !defined(CAN_PLUS) || CAN_PLUS == OFF 13 | #error "No KTECH motor CAN interface!" 14 | #endif 15 | 16 | // KTECH status rate default 1Hz 17 | #ifndef KTECH_STATUS_MS 18 | #define KTECH_STATUS_MS 1000 19 | #endif 20 | 21 | typedef struct ServoKTechSettings { 22 | int16_t model; 23 | int8_t status; 24 | int32_t velocityMax; // maximum velocity in steps/second 25 | int32_t acceleration; // acceleration steps/second/second 26 | } ServoKTechSettings; 27 | 28 | class ServoKTech : public ServoDriver { 29 | public: 30 | // constructor 31 | ServoKTech(uint8_t axisNumber, const ServoKTechSettings *KTechSettings); 32 | 33 | // decodes driver model and sets up the pin modes 34 | bool init(); 35 | 36 | // enable or disable the driver using the enable pin or other method 37 | void enable(bool state); 38 | 39 | // power level to the motor 40 | float setMotorVelocity(float power); 41 | 42 | // request driver status from CAN 43 | void requestStatus(); 44 | 45 | // read the associated driver status from CAN 46 | void requestStatusCallback(uint8_t data[8]); 47 | 48 | const ServoKTechSettings *Settings; 49 | 50 | private: 51 | // read status info. from driver 52 | void readStatus(); 53 | 54 | int canID; 55 | unsigned long lastVelocityUpdateTime = 0; 56 | unsigned long lastStatusUpdateTime = 0; 57 | 58 | void (*callback)() = NULL; 59 | 60 | bool powered = false; 61 | bool sdMode = false; 62 | float currentVelocity = 0.0F; 63 | float acceleration; 64 | float accelerationFs; 65 | bool statusRequestSent = false; 66 | 67 | long lastV = 0; 68 | }; 69 | 70 | #endif 71 | -------------------------------------------------------------------------------- /src/lib/axis/motor/stepDir/generic/Generic.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // axis step/dir motor driver 3 | #pragma once 4 | 5 | #include 6 | #include "../../../../../Common.h" 7 | 8 | #ifdef STEP_DIR_LEGACY_PRESENT 9 | 10 | #include "../../Drivers.h" 11 | #include "../StepDirDriver.h" 12 | 13 | class StepDirGeneric : StepDirDriver { 14 | public: 15 | // constructor 16 | StepDirGeneric(uint8_t axisNumber, const StepDirDriverPins *Pins, const StepDirDriverSettings *Settings); 17 | 18 | // get driver type code 19 | inline char getParameterTypeCode() { return 'S'; } 20 | 21 | // setup driver 22 | bool init(); 23 | 24 | // set microstep mode for tracking 25 | void modeMicrostepTracking(); 26 | 27 | // set microstep mode for slewing 28 | int modeMicrostepSlewing(); 29 | 30 | // set decay mode for tracking 31 | void modeDecayTracking(); 32 | 33 | // set decay mode for slewing 34 | void modeDecaySlewing(); 35 | 36 | // read status info. from driver 37 | inline void readStatus() {}; 38 | 39 | private: 40 | 41 | // checks if decay pin should be HIGH/LOW for a given decay setting 42 | int8_t getDecayPinState(int8_t decay); 43 | 44 | // checkes if decay control is on the M2 pin 45 | bool isDecayOnM2(); 46 | 47 | uint8_t microstepBitCode = 0; 48 | uint8_t microstepBitCodeM0 = 0; 49 | uint8_t microstepBitCodeM1 = 0; 50 | uint8_t microstepBitCodeM2 = 0; 51 | uint8_t microstepBitCodeGoto = 0; 52 | uint8_t microstepBitCodeGotoM0 = 0; 53 | uint8_t microstepBitCodeGotoM1 = 0; 54 | uint8_t microstepBitCodeGotoM2 = 0; 55 | int16_t m0Pin = OFF; 56 | int16_t m1Pin = OFF; 57 | int16_t m2Pin = OFF; 58 | int16_t decayPin = OFF; 59 | }; 60 | 61 | #endif 62 | -------------------------------------------------------------------------------- /src/lib/axis/motor/stepDir/tmcLegacy/LegacySPI.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // axis step/dir motor driver 3 | #pragma once 4 | 5 | #include 6 | #include "../../../../../Common.h" 7 | 8 | #if !defined(DRIVER_TMC_STEPPER) && defined(STEP_DIR_TMC_SPI_PRESENT) 9 | 10 | #include "TmcSPI.h" 11 | #include "../StepDirDriver.h" 12 | 13 | class StepDirTmcSPI : public StepDirDriver { 14 | public: 15 | // constructor 16 | StepDirTmcSPI(uint8_t axisNumber, const StepDirDriverPins *Pins, const StepDirDriverSettings *Settings); 17 | 18 | // get driver type code 19 | inline char getParameterTypeCode() { return 'T'; } 20 | 21 | // setup driver 22 | bool init(); 23 | 24 | // validate driver parameters 25 | bool validateParameters(float param1, float param2, float param3, float param4, float param5, float param6); 26 | 27 | // set microstep mode for tracking 28 | void modeMicrostepTracking(); 29 | 30 | // set microstep mode for slewing 31 | int modeMicrostepSlewing(); 32 | 33 | // set decay mode for tracking 34 | void modeDecayTracking(); 35 | 36 | // set decay mode for slewing 37 | void modeDecaySlewing(); 38 | 39 | // secondary way to power down not using the enable pin 40 | bool enable(bool state); 41 | 42 | // calibrate the motor driver if required 43 | void calibrateDriver(); 44 | 45 | TmcSPI driver; 46 | 47 | private: 48 | // read status info. from driver 49 | void readStatus(); 50 | 51 | // checks if decay pin should be HIGH/LOW for a given decay setting 52 | int8_t getDecayPinState(int8_t decay); 53 | }; 54 | 55 | #endif 56 | -------------------------------------------------------------------------------- /src/lib/bluetooth/BluetoothManager.h: -------------------------------------------------------------------------------- 1 | // bluetooth manager 2 | #pragma once 3 | 4 | #include "../../Common.h" 5 | 6 | #if SERIAL_BT_MODE == MASTER 7 | 8 | #include "Bluetooth.defaults.h" 9 | 10 | #ifndef ESP32 11 | #error "Configuration (Config.h): No Bluetooth support is present for this device" 12 | #endif 13 | 14 | typedef struct BluetoothStationSettings { 15 | char host[16]; 16 | char address[18]; 17 | char passkey[5]; 18 | } BluetoothStationSettings; 19 | 20 | #ifndef BluetoothStationCount 21 | // number of bluetooth stations supported, between 1 and 6 22 | #define BluetoothStationCount 3 23 | #endif 24 | #define BluetoothSettingsSize (32 + BluetoothStationCount*39) 25 | typedef struct BluetoothSettings { 26 | char masterPassword[32]; 27 | BluetoothStationSettings station[BluetoothStationCount]; 28 | } BluetoothSettings; 29 | 30 | class BluetoothManager { 31 | public: 32 | bool init(); 33 | void disconnect(); 34 | void setStation(int number); 35 | void readSettings(); 36 | void writeSettings(); 37 | 38 | BluetoothStationSettings *sta; 39 | 40 | BluetoothSettings settings = { 41 | PASSWORD_DEFAULT, 42 | 43 | { 44 | #if BluetoothStationCount > 0 45 | {STA1_BT_NAME, STA1_BT_ADDR, STA1_BT_PASSKEY}, 46 | #endif 47 | #if BluetoothStationCount > 1 48 | {STA2_BT_NAME, STA2_BT_ADDR, STA2_BT_PASSKEY}, 49 | #endif 50 | #if BluetoothStationCount > 2 51 | {STA3_BT_NAME, STA3_BT_ADDR, STA3_BT_PASSKEY}, 52 | #endif 53 | #if BluetoothStationCount > 3 54 | {STA4_BT_NAME, STA4_BT_ADDR, STA4_BT_PASSKEY}, 55 | #endif 56 | #if BluetoothStationCount > 4 57 | {STA5_BT_NAME, STA5_BT_ADDR, STA5_BT_PASSKEY}, 58 | #endif 59 | #if BluetoothStationCount > 5 60 | {STA6_BT_NAME, STA6_BT_ADDR, STA6_BT_PASSKEY}, 61 | #endif 62 | } 63 | }; 64 | 65 | bool active = false; 66 | bool settingsReady = false; 67 | int stationNumber = 1; 68 | 69 | private: 70 | 71 | }; 72 | 73 | extern BluetoothManager bluetoothManager; 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/lib/calendars/Calendars.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Gregorian and Julian calendars 3 | #pragma once 4 | 5 | #include 6 | 7 | #define CALENDARS_PRESENT 8 | 9 | #ifdef CALENDARS_PRESENT 10 | 11 | typedef struct GregorianDate { 12 | int16_t year; 13 | uint8_t month; 14 | uint8_t day; 15 | double hour; 16 | bool valid; 17 | } GregorianDate; 18 | 19 | #define JulianDateSize 16 20 | typedef struct JulianDate { 21 | double day; 22 | double hour; 23 | } JulianDate; 24 | 25 | class Calendars { 26 | public: 27 | // convert from Gregorian to Julian date/time 28 | JulianDate gregorianToJulian(GregorianDate date); 29 | 30 | // convert from Julian to Gregorian date/time 31 | GregorianDate julianToGregorian(JulianDate julianDate); 32 | 33 | // convert from Gregorian to Julian date (does not handle hours) 34 | JulianDate gregorianToJulianDay(GregorianDate date); 35 | 36 | // convert from Julian to Gregorian date (does not handle hours) 37 | GregorianDate julianDayToGregorian(JulianDate julianDate); 38 | 39 | private: 40 | }; 41 | 42 | extern Calendars calendars; 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /src/lib/canPlus/CanPlus.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS != OFF 8 | #include "san/San.h" 9 | #include "esp32/Esp32.h" 10 | #include "mcp2515/Mcp2515.h" 11 | #include "teensy4/Can0.h" 12 | #include "teensy4/Can1.h" 13 | #include "teensy4/Can2.h" 14 | #include "teensy4/Can3.h" 15 | #endif 16 | -------------------------------------------------------------------------------- /src/lib/canPlus/esp32/Esp32.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN_ESP32 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #ifndef ESP32 12 | #error "Configuration (Config.h): Setting CAN_PLUS CAN_ESP32 requires an ESP32 microcontroller." 13 | #endif 14 | 15 | class CanPlusESP32 : public CanPlus { 16 | public: 17 | CanPlusESP32(); 18 | void init(); 19 | int writePacket(int id, uint8_t *buffer, size_t size); 20 | void poll(); 21 | 22 | private: 23 | 24 | }; 25 | 26 | extern CanPlusESP32 canPlus; 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /src/lib/canPlus/mcp2515/Mcp2515.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN_MCP2515 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #ifndef CAN_CLOCK 12 | #define CAN_CLOCK MCP_8MHZ 13 | #endif 14 | 15 | #ifndef CAN_CS_PIN 16 | // MCP2515 CAN controller CS pin for SPI comms on the microcontroller default interface 17 | #define CAN_CS_PIN 5 18 | #endif 19 | 20 | #ifndef CAN_INT_PIN 21 | // MCP2515 CAN controller interrupt pin is required 22 | #define CAN_INT_PIN 15 23 | #endif 24 | 25 | class CanPlusMCP2515 : public CanPlus { 26 | public: 27 | CanPlusMCP2515(); 28 | void init(); 29 | int writePacket(int id, uint8_t *buffer, size_t size); 30 | void poll(); 31 | 32 | private: 33 | 34 | }; 35 | 36 | extern CanPlusMCP2515 canPlus; 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /src/lib/canPlus/san/San.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN_SAN 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | class CanPlusSan : public CanPlus { 12 | public: 13 | CanPlusSan(); 14 | void init(); 15 | int beginPacket(int id); 16 | int endPacket(); 17 | int write(uint8_t byte); 18 | int write(uint8_t *buffer, size_t size); 19 | int writePacket(int id, uint8_t *buffer, size_t size); 20 | void poll(int packetSize); 21 | 22 | private: 23 | 24 | }; 25 | 26 | extern CanPlusSan canPlus; 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can0.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | 4 | #include "Can0.h" 5 | 6 | #if defined(CAN_PLUS) && CAN_PLUS == CAN0_TEENSY4 7 | 8 | #include "../../tasks/OnTask.h" 9 | 10 | void canT4Recv0(const CAN_message_t &msg) { canPlus.poll(msg); } 11 | void canT4Poll0() { canPlus.events(); } 12 | 13 | FlexCAN_T4 can0; 14 | 15 | CanPlus0Teesny4::CanPlus0Teesny4() { 16 | } 17 | 18 | void CanPlus0Teesny4::init() { 19 | VF("MSG: CanPlus, CAN_TEENSY4 CAN0 Start..."); 20 | can0.begin(); 21 | can0.setBaudRate(CAN_BAUD); 22 | can0.setMaxMB(16); 23 | can0.enableFIFO(); 24 | can0.enableFIFOInterrupt(); 25 | can0.onReceive(canT4Recv0); 26 | ready = true; 27 | 28 | if (ready) { 29 | VLF("success"); 30 | 31 | VF("MSG: CanPlus, start callback monitor task (rate "); V(CAN_RECV_RATE_MS); VF("ms priority 3)... "); 32 | if (tasks.add(CAN_RECV_RATE_MS, 0, true, 3, canT4Poll0, "SysCan0")) { VLF("success"); } else { VLF("FAILED!"); } 33 | } else { 34 | VLF("FAILED!"); 35 | } 36 | } 37 | 38 | int CanPlus0Teesny4::writePacket(int id, uint8_t *buffer, size_t size) { 39 | if (!ready) return 0; 40 | if (size < 1 || size > 8) return 0; 41 | 42 | CAN_message_t msg; 43 | 44 | msg.id = id; 45 | msg.len = 8; 46 | for (int i = 0; i < msg.len; i++) msg.buf[i] = buffer[i]; 47 | can0.write(msg); 48 | 49 | return 1; 50 | } 51 | 52 | void CanPlus0Teesny4::poll(const CAN_message_t &msg) { 53 | if (!ready) return; 54 | 55 | if (msg.flags.overrun) return; 56 | // extend Id not supported 57 | if (msg.flags.extended) return; 58 | // mesage lengths other than 8 not supported 59 | if (msg.len != 8) return; 60 | 61 | uint8_t buffer[8]; 62 | for (int i = 0; i < msg.len; i++) buffer[i] = msg.buf[i]; 63 | 64 | callbackProcess(msg.id, buffer, msg.len); 65 | } 66 | 67 | void CanPlus0Teesny4::events() { 68 | can0.events(); 69 | } 70 | 71 | #if CAN_PLUS_DEFAULT == CAN0_TEENSY4 72 | CanPlus0Teesny4 canPlus; 73 | #endif 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can0.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN0_TEENSY4 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #include // https://github.com/tonton81/FlexCAN_T4 12 | 13 | #if !defined(ARDUINO_TEENSY40) && !defined(ARDUINO_TEENSY41) 14 | #error "Configuration (Config.h): Setting CAN_PLUS CAN_TEENSY4 requires an Teensy4.0 or Teensy4.1 microcontroller." 15 | #endif 16 | 17 | #ifndef CAN_PLUS_DEFAULT 18 | #define CAN_PLUS_DEFAULT CAN0_TEENSY4 19 | #endif 20 | 21 | class CanPlus0Teesny4 : public CanPlus { 22 | public: 23 | CanPlus0Teesny4(); 24 | void init(); 25 | int writePacket(int id, uint8_t *buffer, size_t size); 26 | void poll(const CAN_message_t &msg); 27 | void events(); 28 | 29 | private: 30 | 31 | }; 32 | 33 | #if CAN_PLUS_DEFAULT == CAN0_TEENSY4 34 | extern CanPlus0Teesny4 canPlus; 35 | #endif 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can1.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | 4 | #include "Can1.h" 5 | 6 | #if defined(CAN_PLUS) && CAN_PLUS == CAN1_TEENSY4 7 | 8 | #include "../../tasks/OnTask.h" 9 | 10 | void canT4Recv1(const CAN_message_t &msg) { canPlus.poll(msg); } 11 | void canT4Poll1() { canPlus.events(); } 12 | 13 | FlexCAN_T4 can1; 14 | 15 | CanPlus1Teesny4::CanPlus1Teesny4() { 16 | } 17 | 18 | void CanPlus1Teesny4::init() { 19 | VF("MSG: CanPlus, CAN_TEENSY4 CAN1 Start..."); 20 | can1.begin(); 21 | can1.setBaudRate(CAN_BAUD); 22 | can1.setMaxMB(16); 23 | can1.enableFIFO(); 24 | can1.enableFIFOInterrupt(); 25 | can1.onReceive(canT4Recv1); 26 | ready = true; 27 | 28 | if (ready) { 29 | VLF("success"); 30 | 31 | VF("MSG: CanPlus, start callback monitor task (rate "); V(CAN_RECV_RATE_MS); VF("ms priority 3)... "); 32 | if (tasks.add(CAN_RECV_RATE_MS, 0, true, 3, canT4Poll1, "SysCan1")) { VLF("success"); } else { VLF("FAILED!"); } 33 | } else { 34 | VLF("FAILED!"); 35 | } 36 | } 37 | 38 | int CanPlus1Teesny4::writePacket(int id, uint8_t *buffer, size_t size) { 39 | if (!ready) return 0; 40 | if (size < 1 || size > 8) return 0; 41 | 42 | CAN_message_t msg; 43 | 44 | msg.id = id; 45 | msg.len = 8; 46 | for (int i = 0; i < msg.len; i++) msg.buf[i] = buffer[i]; 47 | can1.write(msg); 48 | 49 | return 1; 50 | } 51 | 52 | void CanPlus1Teesny4::poll(const CAN_message_t &msg) { 53 | if (!ready) return; 54 | 55 | if (msg.flags.overrun) return; 56 | // extend Id not supported 57 | if (msg.flags.extended) return; 58 | // mesage lengths other than 8 not supported 59 | if (msg.len != 8) return; 60 | 61 | uint8_t buffer[8]; 62 | for (int i = 0; i < msg.len; i++) buffer[i] = msg.buf[i]; 63 | 64 | callbackProcess(msg.id, buffer, msg.len); 65 | } 66 | 67 | void CanPlus1Teesny4::events() { 68 | can1.events(); 69 | } 70 | 71 | #if CAN_PLUS_DEFAULT == CAN1_TEENSY4 72 | CanPlus1Teesny4 canPlus; 73 | #endif 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can1.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN1_TEENSY4 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #include // https://github.com/tonton81/FlexCAN_T4 12 | 13 | #if !defined(ARDUINO_TEENSY40) && !defined(ARDUINO_TEENSY41) 14 | #error "Configuration (Config.h): Setting CAN_PLUS CAN_TEENSY4 requires an Teensy4.0 or Teensy4.1 microcontroller." 15 | #endif 16 | 17 | #ifndef CAN_PLUS_DEFAULT 18 | #define CAN_PLUS_DEFAULT CAN1_TEENSY4 19 | #endif 20 | 21 | class CanPlus1Teesny4 : public CanPlus { 22 | public: 23 | CanPlus1Teesny4(); 24 | void init(); 25 | int writePacket(int id, uint8_t *buffer, size_t size); 26 | void poll(const CAN_message_t &msg); 27 | void events(); 28 | 29 | private: 30 | 31 | }; 32 | 33 | #if CAN_PLUS_DEFAULT == CAN1_TEENSY4 34 | extern CanPlus1Teesny4 canPlus; 35 | #endif 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can2.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | 4 | #include "Can2.h" 5 | 6 | #if defined(CAN_PLUS) && CAN_PLUS == CAN2_TEENSY4 7 | 8 | #include "../../tasks/OnTask.h" 9 | 10 | void canT4Recv2(const CAN_message_t &msg) { canPlus.poll(msg); } 11 | void canT4Poll2() { canPlus.events(); } 12 | 13 | FlexCAN_T4 can2; 14 | 15 | CanPlus2Teesny4::CanPlus2Teesny4() { 16 | } 17 | 18 | void CanPlus2Teesny4::init() { 19 | VF("MSG: CanPlus, CAN_TEENSY4 CAN2 Start..."); 20 | can2.begin(); 21 | can2.setBaudRate(CAN_BAUD); 22 | can2.setMaxMB(16); 23 | can2.enableFIFO(); 24 | can2.enableFIFOInterrupt(); 25 | can2.onReceive(canT4Recv2); 26 | ready = true; 27 | 28 | if (ready) { 29 | VLF("success"); 30 | 31 | VF("MSG: CanPlus, start callback monitor task (rate "); V(CAN_RECV_RATE_MS); VF("ms priority 3)... "); 32 | if (tasks.add(CAN_RECV_RATE_MS, 0, true, 3, canT4Poll2, "SysCan2")) { VLF("success"); } else { VLF("FAILED!"); } 33 | } else { 34 | VLF("FAILED!"); 35 | } 36 | } 37 | 38 | int CanPlus2Teesny4::writePacket(int id, uint8_t *buffer, size_t size) { 39 | if (!ready) return 0; 40 | if (size < 1 || size > 8) return 0; 41 | 42 | CAN_message_t msg; 43 | 44 | msg.id = id; 45 | msg.len = 8; 46 | for (int i = 0; i < msg.len; i++) msg.buf[i] = buffer[i]; 47 | can2.write(msg); 48 | 49 | return 1; 50 | } 51 | 52 | void CanPlus2Teesny4::poll(const CAN_message_t &msg) { 53 | if (!ready) return; 54 | 55 | if (msg.flags.overrun) return; 56 | // extend Id not supported 57 | if (msg.flags.extended) return; 58 | // mesage lengths other than 8 not supported 59 | if (msg.len != 8) return; 60 | 61 | uint8_t buffer[8]; 62 | for (int i = 0; i < msg.len; i++) buffer[i] = msg.buf[i]; 63 | 64 | callbackProcess(msg.id, buffer, msg.len); 65 | } 66 | 67 | void CanPlus2Teesny4::events() { 68 | can2.events(); 69 | } 70 | 71 | #if CAN_PLUS_DEFAULT == CAN2_TEENSY4 72 | CanPlus2Teesny4 canPlus; 73 | #endif 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can2.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN2_TEENSY4 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #include // https://github.com/tonton81/FlexCAN_T4 12 | 13 | #if !defined(ARDUINO_TEENSY40) && !defined(ARDUINO_TEENSY41) 14 | #error "Configuration (Config.h): Setting CAN_PLUS CAN_TEENSY4 requires an Teensy4.0 or Teensy4.1 microcontroller." 15 | #endif 16 | 17 | #ifndef CAN_PLUS_DEFAULT 18 | #define CAN_PLUS_DEFAULT CAN2_TEENSY4 19 | #endif 20 | 21 | class CanPlus2Teesny4 : public CanPlus { 22 | public: 23 | CanPlus2Teesny4(); 24 | void init(); 25 | int writePacket(int id, uint8_t *buffer, size_t size); 26 | void poll(const CAN_message_t &msg); 27 | void events(); 28 | 29 | private: 30 | 31 | }; 32 | 33 | #if CAN_PLUS_DEFAULT == CAN2_TEENSY4 34 | extern CanPlus2Teesny4 canPlus; 35 | #endif 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can3.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | 4 | #include "Can3.h" 5 | 6 | #if defined(CAN_PLUS) && CAN_PLUS == CAN3_TEENSY4 7 | 8 | #include "../../tasks/OnTask.h" 9 | 10 | void canT4Recv3(const CAN_message_t &msg) { canPlus.poll(msg); } 11 | void canT4Poll3() { canPlus.events(); } 12 | 13 | FlexCAN_T4 can3; 14 | 15 | CanPlus3Teesny4::CanPlus3Teesny4() { 16 | } 17 | 18 | void CanPlus3Teesny4::init() { 19 | VF("MSG: CanPlus, CAN_TEENSY4 CAN3 Start..."); 20 | can3.begin(); 21 | can3.setBaudRate(CAN_BAUD); 22 | can3.setMaxMB(16); 23 | can3.enableFIFO(); 24 | can3.enableFIFOInterrupt(); 25 | can3.onReceive(canT4Recv3); 26 | ready = true; 27 | 28 | if (ready) { 29 | VLF("success"); 30 | 31 | VF("MSG: CanPlus, start callback monitor task (rate "); V(CAN_RECV_RATE_MS); VF("ms priority 3)... "); 32 | if (tasks.add(CAN_RECV_RATE_MS, 0, true, 3, canT4Poll3, "SysCan3")) { VLF("success"); } else { VLF("FAILED!"); } 33 | } else { 34 | VLF("FAILED!"); 35 | } 36 | } 37 | 38 | int CanPlus3Teesny4::writePacket(int id, uint8_t *buffer, size_t size) { 39 | if (!ready) return 0; 40 | if (size < 1 || size > 8) return 0; 41 | 42 | CAN_message_t msg; 43 | 44 | msg.id = id; 45 | msg.len = 8; 46 | for (int i = 0; i < msg.len; i++) msg.buf[i] = buffer[i]; 47 | can3.write(msg); 48 | 49 | return 1; 50 | } 51 | 52 | void CanPlus3Teesny4::poll(const CAN_message_t &msg) { 53 | if (!ready) return; 54 | 55 | if (msg.flags.overrun) return; 56 | // extend Id not supported 57 | if (msg.flags.extended) return; 58 | // mesage lengths other than 8 not supported 59 | if (msg.len != 8) return; 60 | 61 | uint8_t buffer[8]; 62 | for (int i = 0; i < msg.len; i++) buffer[i] = msg.buf[i]; 63 | 64 | callbackProcess(msg.id, buffer, msg.len); 65 | } 66 | 67 | void CanPlus3Teesny4::events() { 68 | can3.events(); 69 | } 70 | 71 | #if CAN_PLUS_DEFAULT == CAN3_TEENSY4 72 | CanPlus3Teesny4 canPlus; 73 | #endif 74 | 75 | #endif 76 | -------------------------------------------------------------------------------- /src/lib/canPlus/teensy4/Can3.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // CAN library 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | 7 | #if defined(CAN_PLUS) && CAN_PLUS == CAN3_TEENSY4 8 | 9 | #include "../CanPlusBase.h" 10 | 11 | #include // https://github.com/tonton81/FlexCAN_T4 12 | 13 | #if !defined(ARDUINO_TEENSY40) && !defined(ARDUINO_TEENSY41) 14 | #error "Configuration (Config.h): Setting CAN_PLUS CAN_TEENSY4 requires an Teensy4.0 or Teensy4.1 microcontroller." 15 | #endif 16 | 17 | #ifndef CAN_PLUS_DEFAULT 18 | #define CAN_PLUS_DEFAULT CAN3_TEENSY4 19 | #endif 20 | 21 | class CanPlus3Teesny4 : public CanPlus { 22 | public: 23 | CanPlus3Teesny4(); 24 | void init(); 25 | int writePacket(int id, uint8_t *buffer, size_t size); 26 | void poll(const CAN_message_t &msg); 27 | void events(); 28 | 29 | private: 30 | 31 | }; 32 | 33 | #if CAN_PLUS_DEFAULT == CAN3_TEENSY4 34 | extern CanPlus3Teesny4 canPlus; 35 | #endif 36 | 37 | #endif 38 | -------------------------------------------------------------------------------- /src/lib/commands/BufferCmds.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Command processing 3 | #pragma once 4 | 5 | class Buffer { 6 | public: 7 | bool checksum = false; 8 | 9 | void init(int mountType); 10 | 11 | bool add(char c); 12 | char* getCmd(); 13 | char* getParameter(); 14 | char* getSeq(); 15 | bool ready(); 16 | bool flush(); 17 | 18 | private: 19 | int mountType = 0; 20 | char channel; 21 | char (*reader)(); 22 | char (*writer)(char c); 23 | 24 | const static int bufferSize = 80; 25 | char cmd[4] = ""; 26 | char pb[bufferSize] = ""; 27 | char cb[bufferSize] = ""; 28 | int cbp = 0; 29 | char seq = 0; 30 | }; 31 | -------------------------------------------------------------------------------- /src/lib/commands/CommandErrors.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Command processing errors 3 | #pragma once 4 | 5 | typedef enum CommandError { 6 | CE_NONE, CE_0, CE_CMD_UNKNOWN, CE_REPLY_UNKNOWN, CE_PARAM_RANGE, CE_PARAM_FORM, 7 | CE_ALIGN_FAIL, CE_ALIGN_NOT_ACTIVE, CE_NOT_PARKED_OR_AT_HOME, CE_PARKED, 8 | CE_PARK_FAILED, CE_NOT_PARKED, CE_NO_PARK_POSITION_SET, CE_GOTO_FAIL, CE_LIBRARY_FULL, 9 | 10 | // goto/guide errors 11 | CE_SLEW_ERR_BELOW_HORIZON, CE_SLEW_ERR_ABOVE_OVERHEAD, CE_SLEW_ERR_IN_STANDBY, 12 | CE_SLEW_ERR_IN_PARK, CE_SLEW_IN_SLEW, CE_SLEW_ERR_OUTSIDE_LIMITS, CE_SLEW_ERR_HARDWARE_FAULT, 13 | CE_SLEW_IN_MOTION, CE_SLEW_ERR_UNSPECIFIED, 14 | 15 | CE_NULL, CE_1 16 | } CommandError; 17 | -------------------------------------------------------------------------------- /src/lib/commands/SerialWrapper.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // SerialWrapper a single class to allow uniform access to other serial port classes 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #include "../serial/Serial_IP_Wifi.h" 8 | #include "../serial/Serial_IP_Ethernet.h" 9 | 10 | #ifdef MOUNT_PRESENT 11 | #if ST4_INTERFACE == ON && ST4_HAND_CONTROL == ON 12 | #include "../serial/Serial_ST4_Master.h" 13 | #endif 14 | #endif 15 | #include "../serial/Serial_Local.h" 16 | 17 | static uint8_t _wrapper_channels = 0; 18 | 19 | #define isChannel(x) (x == thisChannel) 20 | 21 | class SerialWrapper : public Stream { 22 | public: 23 | SerialWrapper(); 24 | 25 | void begin(); 26 | void begin(long baud); 27 | 28 | void end(); 29 | 30 | virtual size_t write(uint8_t); 31 | virtual size_t write(const uint8_t *, size_t); 32 | virtual int available(void); 33 | virtual int read(void); 34 | virtual int peek(void); 35 | virtual void flush(void); 36 | 37 | inline size_t write(unsigned long n) { return write((uint8_t)n); } 38 | inline size_t write(long n) { return write((uint8_t)n); } 39 | inline size_t write(unsigned int n) { return write((uint8_t)n); } 40 | inline size_t write(int n) { return write((uint8_t)n); } 41 | 42 | inline bool hasChannel(uint8_t channel) { return bitRead(_wrapper_channels, channel); } 43 | inline void setChannel(uint8_t channel) { bitSet(_wrapper_channels, channel); } 44 | inline void clrChannel(uint8_t channel) { bitClear(_wrapper_channels, channel); } 45 | 46 | using Print::write; 47 | 48 | private: 49 | uint8_t thisChannel = 0; 50 | }; 51 | -------------------------------------------------------------------------------- /src/lib/commands/commands.ino: -------------------------------------------------------------------------------- 1 | // Placeholder file 2 | // Nothing to see here ... 3 | // 4 | // This file is only present so the Arduino IDE can edit the .h file(s) 5 | -------------------------------------------------------------------------------- /src/lib/debug/Debug.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Helper macros for debugging, with less typing 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #if DEBUG == PROFILER 8 | #define TASKS_PROFILER_ENABLE 9 | #endif 10 | 11 | #if defined(DEBUG) && DEBUG != OFF && DEBUG != PROFILER 12 | #if defined(REMOTE) && DEBUG == REMOTE 13 | // echo strings to OnStep debug interface (supports embedded spaces and cr/lf) 14 | extern void debugPrint(const char* s); 15 | extern bool debugRemoteConnected; 16 | 17 | #define D(x) { if (debugRemoteConnected) { SERIAL_ONSTEP.print(":EC"); SERIAL_ONSTEP.print(x); SERIAL_ONSTEP.print("#"); delay(50); } } 18 | #define DF(x) { if (debugRemoteConnected) { SERIAL_ONSTEP.print(":EC"); debugPrint(x); SERIAL_ONSTEP.print("#"); delay(50); } } 19 | #define DL(x) { if (debugRemoteConnected) { SERIAL_ONSTEP.print(":EC"); SERIAL_ONSTEP.print(x); SERIAL_ONSTEP.print("&#"); delay(50); } } 20 | #define DLF(x) { if (debugRemoteConnected) { SERIAL_ONSTEP.print(":EC"); debugPrint(x); SERIAL_ONSTEP.print("&#"); delay(50); } } 21 | #else 22 | #define D(x) SERIAL_DEBUG.print(x) 23 | #define DF(x) SERIAL_DEBUG.print(F(x)) 24 | #define DL(x) SERIAL_DEBUG.println(x) 25 | #define DLF(x) SERIAL_DEBUG.println(F(x)) 26 | #endif 27 | #define D1(x) { static long t = 0; if (millis() > t + 1000L) { D(x); t = millis(); } } 28 | #define DL1(x) { static long t = 0; if (millis() > t + 1000L) { DL(x); t = millis(); } } 29 | #else 30 | #define D(x) 31 | #define DF(x) 32 | #define DL(x) 33 | #define D1(x) 34 | #define DL1(x) 35 | #define DLF(x) 36 | #endif 37 | 38 | #if (defined(VERBOSE) && DEBUG == VERBOSE) || (defined(REMOTE) && DEBUG == REMOTE) 39 | #define V(x) D(x) 40 | #define VF(x) DF(x) 41 | #define VL(x) DL(x) 42 | #define VL1(x) DL1(x) 43 | #define VLF(x) DLF(x) 44 | #else 45 | #define V(x) 46 | #define VF(x) 47 | #define VL(x) 48 | #define VL1(x) 49 | #define VLF(x) 50 | #endif 51 | -------------------------------------------------------------------------------- /src/lib/encoder/Encoder.h: -------------------------------------------------------------------------------- 1 | // general purpose encoder class 2 | #pragma once 3 | 4 | #include "bissc/As37h39bb.h" 5 | #include "bissc/Jtw24.h" 6 | #include "bissc/Jtw26.h" 7 | #include "bissc/Asc85.h" 8 | #include "ktech/KTech.h" 9 | #include "cwCcw/CwCcw.h" 10 | #include "pulseDir/PulseDir.h" 11 | #include "pulseOnly/PulseOnly.h" 12 | #include "quadrature/Quadrature.h" 13 | #include "quadratureEsp32/QuadratureEsp32.h" 14 | #include "serialBridge/SerialBridge.h" 15 | #include "virtualEnc/VirtualEnc.h" 16 | -------------------------------------------------------------------------------- /src/lib/encoder/EncoderBase.cpp: -------------------------------------------------------------------------------- 1 | // general purpose encoder class 2 | 3 | #include "EncoderBase.h" 4 | 5 | #if AXIS1_ENCODER != OFF || AXIS2_ENCODER != OFF || AXIS3_ENCODER != OFF || \ 6 | AXIS4_ENCODER != OFF || AXIS5_ENCODER != OFF || AXIS6_ENCODER != OFF || \ 7 | AXIS7_ENCODER != OFF || AXIS8_ENCODER != OFF || AXIS9_ENCODER != OFF 8 | 9 | // get device ready for use 10 | bool Encoder::init() { 11 | return true; 12 | } 13 | 14 | // set encoder origin 15 | void Encoder::setOrigin(uint32_t count) { 16 | origin = count; 17 | } 18 | 19 | bool Encoder::errorThresholdExceeded() { 20 | unsigned long minute = millis()/60000; 21 | 22 | if (minute != lastMinute) { 23 | errorCount = 0; 24 | 25 | // simulate an encoder error event 26 | //if (minute == 2) error = 30; 27 | 28 | lastMinute = minute; 29 | } 30 | 31 | errorCount += error; 32 | #ifdef ENCODER_WARN_AS_ERROR 33 | errorCount += warn; 34 | #endif 35 | 36 | totalErrorCount += error; 37 | error = 0; 38 | 39 | totalWarningCount += warn; 40 | warn = 0; 41 | 42 | bool errorState = errorCount > ENCODER_ERROR_COUNT_THRESHOLD; 43 | 44 | if (errorState != lastErrorState) { 45 | if (errorState) { 46 | DF("WRN: Encoder"); D(axis); DF(" error, exceeded threshold/minute at "); DL(errorCount); 47 | } else { 48 | VF("MSG: Encoder"); V(axis); VF(" error, cleared"); 49 | } 50 | lastErrorState = errorState; 51 | } 52 | 53 | return errorState; 54 | } 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /src/lib/encoder/bissc/As37h39bb.h: -------------------------------------------------------------------------------- 1 | // Broadcom AS37-H39B-B BISS-C encoders 2 | #pragma once 3 | 4 | #include "Bissc.h" 5 | 6 | #ifdef HAS_AS37_H39B_B 7 | 8 | class As37h39bb : public Bissc { 9 | public: 10 | // initialize BiSS-C encoder 11 | As37h39bb(int16_t maPin, int16_t sloPin, int16_t axis); 12 | 13 | private: 14 | // read encoder position 15 | bool readEnc(uint32_t &position); 16 | 17 | // BiSS-C 6-bit CRC of 41 bit data (16 multi-turn + 23 position + 2 err/wrn) 18 | uint8_t crc6(uint64_t data); 19 | 20 | // BiSS-C 6-bit CRC table (x^6 + x^1 + 1) 21 | uint8_t CRC6[64] = { 22 | 0x00, 0x03, 0x06, 0x05, 0x0C, 0x0F, 0x0A, 0x09, 23 | 0x18, 0x1B, 0x1E, 0x1D, 0x14, 0x17, 0x12, 0x11, 24 | 0x30, 0x33, 0x36, 0x35, 0x3C, 0x3F, 0x3A, 0x39, 25 | 0x28, 0x2B, 0x2E, 0x2D, 0x24, 0x27, 0x22, 0x21, 26 | 0x23, 0x20, 0x25, 0x26, 0x2F, 0x2C, 0x29, 0x2A, 27 | 0x3B, 0x38, 0x3D, 0x3E, 0x37, 0x34, 0x31, 0x32, 28 | 0x13, 0x10, 0x15, 0x16, 0x1F, 0x1C, 0x19, 0x1A, 29 | 0x0B, 0x08, 0x0D, 0x0E, 0x07, 0x04, 0x01, 0x02}; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /src/lib/encoder/bissc/Asc85.h: -------------------------------------------------------------------------------- 1 | // Lika ASC85 25 BIT BISS-C encoder 2 | #pragma once 3 | 4 | #include "Bissc.h" 5 | 6 | #ifdef HAS_LIKA_ASC85 7 | 8 | class LikaAsc85 : public Bissc { 9 | public: 10 | // initialize BiSS-C encoder 11 | LikaAsc85(int16_t maPin, int16_t sloPin, int16_t axis); 12 | 13 | private: 14 | // read encoder position 15 | bool readEnc(uint32_t &position); 16 | 17 | // BiSS-C 6-bit CRC of 27 bit data (25 position + 2 err/wrn) 18 | uint8_t crc6(uint64_t data); 19 | 20 | // BiSS-C 6-bit CRC table (x^6 + x^1 + 1) 21 | uint8_t CRC6[64] = { 22 | 0x00, 0x03, 0x06, 0x05, 0x0C, 0x0F, 0x0A, 0x09, 23 | 0x18, 0x1B, 0x1E, 0x1D, 0x14, 0x17, 0x12, 0x11, 24 | 0x30, 0x33, 0x36, 0x35, 0x3C, 0x3F, 0x3A, 0x39, 25 | 0x28, 0x2B, 0x2E, 0x2D, 0x24, 0x27, 0x22, 0x21, 26 | 0x23, 0x20, 0x25, 0x26, 0x2F, 0x2C, 0x29, 0x2A, 27 | 0x3B, 0x38, 0x3D, 0x3E, 0x37, 0x34, 0x31, 0x32, 28 | 0x13, 0x10, 0x15, 0x16, 0x1F, 0x1C, 0x19, 0x1A, 29 | 0x0B, 0x08, 0x0D, 0x0E, 0x07, 0x04, 0x01, 0x02}; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /src/lib/encoder/bissc/Bissc.h: -------------------------------------------------------------------------------- 1 | // BISS-C encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #ifdef HAS_BISS_C 7 | 8 | // designed according protocol description found in as38-H39e-b-an100.pdf 9 | 10 | // similar broadcom devices have range of 10MHz to 80 KHz 11 | #ifndef BISSC_CLOCK_RATE_KHZ 12 | #define BISSC_CLOCK_RATE_KHZ 4000 13 | #endif 14 | 15 | // default to single turn mode 16 | #ifndef BISSC_SINGLE_TURN 17 | #define BISSC_SINGLE_TURN ON 18 | #endif 19 | 20 | // allow for inverting the signal state to fix incorrect wiring if needed 21 | #ifndef HIGH_SLO 22 | #define HIGH_SLO HIGH 23 | #endif 24 | #ifndef LOW_SLO 25 | #define LOW_SLO LOW 26 | #endif 27 | #ifndef HIGH_MA 28 | #define HIGH_MA HIGH 29 | #endif 30 | #ifndef LOW_MA 31 | #define LOW_MA LOW 32 | #endif 33 | 34 | class Bissc : public Encoder { 35 | public: 36 | // get device ready for use 37 | bool init(); 38 | 39 | // set encoder origin 40 | void setOrigin(uint32_t count); 41 | 42 | // read encoder count 43 | int32_t read(); 44 | 45 | // write encoder position 46 | void write(int32_t count); 47 | 48 | protected: 49 | // read encoder position with error recovery 50 | bool readEncLatest(uint32_t &position); 51 | 52 | // read encoder position 53 | virtual bool readEnc(uint32_t &position); 54 | 55 | uint32_t good = 0; 56 | uint32_t bad = 0; 57 | int16_t axis; 58 | uint16_t nvAddress = 0; 59 | 60 | int16_t maPin; 61 | int16_t sloPin; 62 | 63 | uint32_t lastValidTime = 0; 64 | uint32_t lastValidPosition = 0; 65 | }; 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /src/lib/encoder/bissc/Jtw24.h: -------------------------------------------------------------------------------- 1 | // JTW 24 BIT BISS-C encoders 2 | #pragma once 3 | 4 | #include "Bissc.h" 5 | 6 | #ifdef HAS_JTW_24BIT 7 | 8 | class Jtw24 : public Bissc { 9 | public: 10 | // initialize BiSS-C encoder 11 | Jtw24(int16_t maPin, int16_t sloPin, int16_t axis); 12 | 13 | private: 14 | // read encoder position 15 | bool readEnc(uint32_t &position); 16 | 17 | // BiSS-C 6-bit CRC of 26 bit data (24 position + 2 err/wrn) 18 | uint8_t crc6(uint64_t data); 19 | 20 | // BiSS-C 6-bit CRC table (x^6 + x^1 + 1) 21 | uint8_t CRC6[64] = { 22 | 0x00, 0x03, 0x06, 0x05, 0x0C, 0x0F, 0x0A, 0x09, 23 | 0x18, 0x1B, 0x1E, 0x1D, 0x14, 0x17, 0x12, 0x11, 24 | 0x30, 0x33, 0x36, 0x35, 0x3C, 0x3F, 0x3A, 0x39, 25 | 0x28, 0x2B, 0x2E, 0x2D, 0x24, 0x27, 0x22, 0x21, 26 | 0x23, 0x20, 0x25, 0x26, 0x2F, 0x2C, 0x29, 0x2A, 27 | 0x3B, 0x38, 0x3D, 0x3E, 0x37, 0x34, 0x31, 0x32, 28 | 0x13, 0x10, 0x15, 0x16, 0x1F, 0x1C, 0x19, 0x1A, 29 | 0x0B, 0x08, 0x0D, 0x0E, 0x07, 0x04, 0x01, 0x02}; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /src/lib/encoder/bissc/Jtw26.h: -------------------------------------------------------------------------------- 1 | // JTW 26 BIT BISS-C encoders 2 | #pragma once 3 | 4 | #include "Bissc.h" 5 | 6 | #ifdef HAS_JTW_26BIT 7 | 8 | class Jtw26 : public Bissc { 9 | public: 10 | // initialize BiSS-C encoder 11 | Jtw26(int16_t maPin, int16_t sloPin, int16_t axis); 12 | 13 | private: 14 | // read encoder position 15 | bool readEnc(uint32_t &position); 16 | 17 | // BiSS-C 6-bit CRC of 50 bit data (24 multi-turn + 24 position + 2 err/wrn) 18 | uint8_t crc6(uint64_t data); 19 | 20 | // BiSS-C 6-bit CRC table (x^6 + x^1 + 1) 21 | uint8_t CRC6[64] = { 22 | 0x00, 0x03, 0x06, 0x05, 0x0C, 0x0F, 0x0A, 0x09, 23 | 0x18, 0x1B, 0x1E, 0x1D, 0x14, 0x17, 0x12, 0x11, 24 | 0x30, 0x33, 0x36, 0x35, 0x3C, 0x3F, 0x3A, 0x39, 25 | 0x28, 0x2B, 0x2E, 0x2D, 0x24, 0x27, 0x22, 0x21, 26 | 0x23, 0x20, 0x25, 0x26, 0x2F, 0x2C, 0x29, 0x2A, 27 | 0x3B, 0x38, 0x3D, 0x3E, 0x37, 0x34, 0x31, 0x32, 28 | 0x13, 0x10, 0x15, 0x16, 0x1F, 0x1C, 0x19, 0x1A, 29 | 0x0B, 0x08, 0x0D, 0x0E, 0x07, 0x04, 0x01, 0x02}; 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /src/lib/encoder/cwCcw/CwCcw.h: -------------------------------------------------------------------------------- 1 | // CW/CCW encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == CW_CCW || AXIS2_ENCODER == CW_CCW || AXIS3_ENCODER == CW_CCW || \ 7 | AXIS4_ENCODER == CW_CCW || AXIS5_ENCODER == CW_CCW || AXIS6_ENCODER == CW_CCW || \ 8 | AXIS7_ENCODER == CW_CCW || AXIS8_ENCODER == CW_CCW || AXIS9_ENCODER == CW_CCW 9 | 10 | class CwCcw : public Encoder { 11 | public: 12 | CwCcw(int16_t cwPin, int16_t ccwPin, int16_t axis); 13 | bool init(); 14 | 15 | int32_t read(); 16 | void write(int32_t count); 17 | 18 | private: 19 | int16_t cwPin, ccwPin; 20 | }; 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /src/lib/encoder/ktech/KTech.h: -------------------------------------------------------------------------------- 1 | // KTech in motor encoder 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #ifndef KTECH_SINGLE_TURN 7 | #define KTECH_SINGLE_TURN 65536 8 | #endif 9 | 10 | #ifndef KTECH_SLEW_DIRECT 11 | #define KTECH_SLEW_DIRECT OFF // ON for KTECH trapezoidal move profile or OFF for OnStep move profile 12 | #endif 13 | 14 | #if AXIS1_ENCODER == KTECH_IME || AXIS2_ENCODER == KTECH_IME || AXIS3_ENCODER == KTECH_IME || \ 15 | AXIS4_ENCODER == KTECH_IME || AXIS5_ENCODER == KTECH_IME || AXIS6_ENCODER == KTECH_IME || \ 16 | AXIS7_ENCODER == KTECH_IME || AXIS8_ENCODER == KTECH_IME || AXIS9_ENCODER == KTECH_IME 17 | 18 | class KTechIME : public Encoder { 19 | public: 20 | KTechIME(int16_t axis); 21 | bool init(); 22 | 23 | int32_t read(); 24 | void write(int32_t count); 25 | 26 | void requestPosition(); 27 | void updatePositionCallback(uint8_t data[8]); 28 | 29 | private: 30 | int canID = 0; 31 | void (*callback)() = NULL; 32 | uint32_t lastCountSingleTurn = 0; 33 | int32_t countTurns = 0; 34 | }; 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /src/lib/encoder/pulseDir/PulseDir.h: -------------------------------------------------------------------------------- 1 | // Pulse/Dir encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == PULSE_DIR || AXIS2_ENCODER == PULSE_DIR || AXIS3_ENCODER == PULSE_DIR || \ 7 | AXIS4_ENCODER == PULSE_DIR || AXIS5_ENCODER == PULSE_DIR || AXIS6_ENCODER == PULSE_DIR || \ 8 | AXIS7_ENCODER == PULSE_DIR || AXIS8_ENCODER == PULSE_DIR || AXIS9_ENCODER == PULSE_DIR 9 | 10 | class PulseDir : public Encoder { 11 | public: 12 | PulseDir(int16_t pulsePin, int16_t dirPin, int16_t axis); 13 | bool init(); 14 | 15 | int32_t read(); 16 | void write(int32_t count); 17 | 18 | private: 19 | int16_t pulsePin, dirPin; 20 | }; 21 | 22 | #endif 23 | -------------------------------------------------------------------------------- /src/lib/encoder/pulseOnly/PulseOnly.h: -------------------------------------------------------------------------------- 1 | // Pulse only encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == PULSE_ONLY || AXIS2_ENCODER == PULSE_ONLY || AXIS3_ENCODER == PULSE_ONLY || \ 7 | AXIS4_ENCODER == PULSE_ONLY || AXIS5_ENCODER == PULSE_ONLY || AXIS6_ENCODER == PULSE_ONLY || \ 8 | AXIS7_ENCODER == PULSE_ONLY || AXIS8_ENCODER == PULSE_ONLY || AXIS9_ENCODER == PULSE_ONLY 9 | 10 | class PulseOnly : public Encoder { 11 | public: 12 | PulseOnly(int16_t pulsePin, int16_t *direction, int16_t axis); 13 | bool init(); 14 | 15 | int32_t read(); 16 | void write(int32_t count); 17 | 18 | void setDirection(volatile int8_t *direction); 19 | 20 | private: 21 | int16_t pulsePin; 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /src/lib/encoder/quadrature/Quadrature.h: -------------------------------------------------------------------------------- 1 | // A/B Quadrature encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == AB || AXIS2_ENCODER == AB || AXIS3_ENCODER == AB || \ 7 | AXIS4_ENCODER == AB || AXIS5_ENCODER == AB || AXIS6_ENCODER == AB || \ 8 | AXIS7_ENCODER == AB || AXIS8_ENCODER == AB || AXIS9_ENCODER == AB 9 | 10 | // for example: 11 | // Quadrature encoder1(AXIS1_ENCODER_A_PIN, AXIS1_ENCODER_B_PIN, 1); 12 | 13 | // Phase 1: LLHH LLHH 14 | // Phase 2: LHHL LHHL 15 | // ...00 01 11 10 00 01 11 10 00 01 11 10... 16 | 17 | class Quadrature : public Encoder { 18 | public: 19 | Quadrature(int16_t APin, int16_t BPin, int16_t axis); 20 | bool init(); 21 | 22 | int32_t read(); 23 | void write(int32_t count); 24 | 25 | void A(const int16_t pin); 26 | void B(const int16_t pin); 27 | 28 | private: 29 | int16_t axis; 30 | 31 | int16_t APin = OFF; 32 | int16_t BPin = OFF; 33 | 34 | volatile int16_t stateA; 35 | volatile int16_t stateB; 36 | volatile int16_t lastA; 37 | volatile int16_t lastB; 38 | }; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /src/lib/encoder/quadratureEsp32/QuadratureEsp32.cpp: -------------------------------------------------------------------------------- 1 | // A/B Quadrature encoders (fast ESP32 hardware decode) 2 | 3 | #include "QuadratureEsp32.h" 4 | 5 | #if AXIS1_ENCODER == AB_ESP32 || AXIS2_ENCODER == AB_ESP32 || AXIS3_ENCODER == AB_ESP32 || \ 6 | AXIS4_ENCODER == AB_ESP32 || AXIS5_ENCODER == AB_ESP32 || AXIS6_ENCODER == AB_ESP32 || \ 7 | AXIS7_ENCODER == AB_ESP32 || AXIS8_ENCODER == AB_ESP32 || AXIS9_ENCODER == AB_ESP32 8 | 9 | // for example: 10 | // QuadratureEsp32 encoder1(AXIS1_ENCODER_A_PIN, AXIS1_ENCODER_B_PIN, 1); 11 | 12 | QuadratureEsp32::QuadratureEsp32(int16_t APin, int16_t BPin, int16_t axis) { 13 | if (axis < 1 || axis > 9) return; 14 | this->APin = APin; 15 | this->BPin = BPin; 16 | } 17 | 18 | bool QuadratureEsp32::init() { 19 | if (ready) return true; 20 | 21 | ab = new ESP32Encoder; 22 | if (ab == NULL) { 23 | DF("ERR: Encoder QuadratureEsp32"); D(axis); DLF(" init(), didn't get instance!"); 24 | return false; 25 | } 26 | 27 | ab->attachFullQuad(APin, BPin); 28 | ab->setCount(0); 29 | 30 | ready = true; 31 | return true; 32 | } 33 | 34 | int32_t QuadratureEsp32::read() { 35 | if (!ready) return 0; 36 | 37 | count = (int32_t)ab->getCount(); 38 | 39 | return count + origin; 40 | } 41 | 42 | void QuadratureEsp32::write(int32_t count) { 43 | if (!ready) return; 44 | 45 | count -= origin; 46 | 47 | ab->setCount(count); 48 | } 49 | 50 | #endif 51 | -------------------------------------------------------------------------------- /src/lib/encoder/quadratureEsp32/QuadratureEsp32.h: -------------------------------------------------------------------------------- 1 | // A/B Quadrature encoders (fast ESP32 hardware decode) 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == AB_ESP32 || AXIS2_ENCODER == AB_ESP32 || AXIS3_ENCODER == AB_ESP32 || \ 7 | AXIS4_ENCODER == AB_ESP32 || AXIS5_ENCODER == AB_ESP32 || AXIS6_ENCODER == AB_ESP32 || \ 8 | AXIS7_ENCODER == AB_ESP32 || AXIS8_ENCODER == AB_ESP32 || AXIS9_ENCODER == AB_ESP32 9 | 10 | #include // https://github.com/madhephaestus/ESP32Encoder/tree/master 11 | 12 | // for example: 13 | // QuadratureEsp32 encoder1(AXIS1_ENCODER_A_PIN, AXIS1_ENCODER_B_PIN, 1); 14 | 15 | // Phase 1: LLHH LLHH 16 | // Phase 2: LHHL LHHL 17 | // ...00 01 11 10 00 01 11 10 00 01 11 10... 18 | 19 | class QuadratureEsp32 : public Encoder { 20 | public: 21 | QuadratureEsp32(int16_t APin, int16_t BPin, int16_t axis); 22 | bool init(); 23 | 24 | int32_t read(); 25 | void write(int32_t count); 26 | 27 | ESP32Encoder *ab; 28 | 29 | private: 30 | int16_t axis; 31 | 32 | int16_t APin = OFF; 33 | int16_t BPin = OFF; 34 | }; 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /src/lib/encoder/serialBridge/SerialBridge.h: -------------------------------------------------------------------------------- 1 | // Serial bridge encoder 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if (AXIS1_ENCODER == SERIAL_BRIDGE || AXIS2_ENCODER == SERIAL_BRIDGE || AXIS3_ENCODER == SERIAL_BRIDGE || \ 7 | AXIS4_ENCODER == SERIAL_BRIDGE || AXIS5_ENCODER == SERIAL_BRIDGE || AXIS6_ENCODER == SERIAL_BRIDGE || \ 8 | AXIS7_ENCODER == SERIAL_BRIDGE || AXIS8_ENCODER == SERIAL_BRIDGE || AXIS9_ENCODER == SERIAL_BRIDGE) && defined(SERIAL_ENCODER) 9 | 10 | #ifndef SERIAL_ENCODER_BAUD 11 | #define SERIAL_ENCODER_BAUD 460800 12 | #endif 13 | 14 | class SerialBridge : public Encoder { 15 | public: 16 | SerialBridge(int16_t axis); 17 | int32_t read(); 18 | void write(int32_t count); 19 | bool errorThresholdExceeded() { return errorDetected; } 20 | 21 | private: 22 | int32_t raw(); 23 | 24 | int32_t offset = 0; 25 | 26 | char channel[2] = "0"; 27 | unsigned long lastReadMillis = 0; 28 | bool errorDetected = false; 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/encoder/virtualEnc/VirtualEnc.h: -------------------------------------------------------------------------------- 1 | // Pulse only encoders 2 | #pragma once 3 | 4 | #include "../EncoderBase.h" 5 | 6 | #if AXIS1_ENCODER == VIRTUAL || AXIS2_ENCODER == VIRTUAL || AXIS3_ENCODER == VIRTUAL || \ 7 | AXIS4_ENCODER == VIRTUAL || AXIS5_ENCODER == VIRTUAL || AXIS6_ENCODER == VIRTUAL || \ 8 | AXIS7_ENCODER == VIRTUAL || AXIS8_ENCODER == VIRTUAL || AXIS9_ENCODER == VIRTUAL 9 | 10 | class VirtualEnc : public Encoder { 11 | public: 12 | VirtualEnc(int16_t axis); 13 | bool init(); 14 | 15 | int32_t read(); 16 | void write(int32_t count); 17 | 18 | void setVelocity(float countsPerSec); 19 | void setDirection(volatile int8_t *direction); 20 | 21 | private: 22 | uint8_t virtualEncoderHandle = 0; 23 | long countsPerSec = 0; 24 | long timerRateMs = 3000/HAL_FRACTIONAL_SEC; // (1.0/HAL_FRACTIONAL_SEC)*3*1000 25 | }; 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /src/lib/ethernet/cmdServer/CmdServer.h: -------------------------------------------------------------------------------- 1 | // ethernet IP command server 2 | #pragma once 3 | 4 | #include "../../../Common.h" 5 | #include "../EthernetManager.h" 6 | 7 | #if OPERATIONAL_MODE >= ETHERNET_FIRST && OPERATIONAL_MODE <= ETHERNET_LAST && COMMAND_SERVER != OFF 8 | 9 | class CmdServer { 10 | public: 11 | CmdServer(uint32_t port, long clientTimeoutMs, bool persist = false); 12 | void begin(); 13 | void handleClient(); 14 | 15 | private: 16 | EthernetServer *cmdSvr; 17 | EthernetClient cmdSvrClient; 18 | 19 | unsigned long clientTimeoutMs; 20 | unsigned long clientEndTimeMs = 0; 21 | bool persist; 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /src/lib/gpioEx/GpioBase.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // standard external GPIO library 3 | 4 | #include "GpioBase.h" 5 | 6 | #if defined(GPIO_DEVICE) && GPIO_DEVICE != OFF 7 | 8 | bool Gpio::command(char *reply, char *command, char *parameter, bool *supressFrame, bool *numericReply, CommandError *commandError) { 9 | UNUSED(reply); 10 | UNUSED(command); 11 | UNUSED(parameter); 12 | UNUSED(supressFrame); 13 | UNUSED(numericReply); 14 | UNUSED(commandError); 15 | return false; 16 | } 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /src/lib/gpioEx/GpioEx.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // standard external GPIO library 3 | #pragma once 4 | 5 | #include "ds2413/Ds2413.h" 6 | #include "mcp23008/Mcp23008.h" 7 | #include "mcp23017/Mcp23017.h" 8 | #include "tca9555/Tca9555.h" 9 | #include "pcf8575/Pcf8575.h" 10 | #include "pcf8574/Pcf8574.h" 11 | #include "sws/Sws.h" 12 | #include "ssr74HC595/Ssr74HC595.h" 13 | -------------------------------------------------------------------------------- /src/lib/gpioEx/ds2413/Ds2413.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Dallas/Maxim 1-Wire DS2413 device support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == DS2413 8 | 9 | #define DS2413_MAX_DEVICES 2 10 | 11 | class GpioDs2413 : public Gpio { 12 | public: 13 | // scan for DS2413 devices on the 1-wire bus 14 | bool init(); 15 | 16 | // set GPIO pin mode for INPUT or OUTPUT (both pins of any device must be in the same mode) 17 | void pinMode(int pin, int mode); 18 | 19 | // get GPIO pin state 20 | int digitalRead(int pin); 21 | 22 | // set GPIO pin state 23 | void digitalWrite(int pin, int value); 24 | 25 | // update the DS2413 26 | void poll(); 27 | 28 | private: 29 | bool found = false; 30 | uint8_t deviceCount = 0; 31 | int lastValidPin = -1; 32 | 33 | uint8_t address[DS2413_MAX_DEVICES][8]; 34 | 35 | int mode[DS2413_MAX_DEVICES] = {INPUT, INPUT}; 36 | uint8_t state[DS2413_MAX_DEVICES*2] = {false, false, false, false}; 37 | int16_t lastState[DS2413_MAX_DEVICES*2] = {INVALID, INVALID, INVALID, INVALID}; 38 | 39 | unsigned long goodUntil[DS2413_MAX_DEVICES] = {0, 0}; 40 | }; 41 | 42 | extern GpioDs2413 gpio; 43 | 44 | #endif 45 | -------------------------------------------------------------------------------- /src/lib/gpioEx/mcp23008/Mcp23008.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C MCP23008 GPIO support 3 | 4 | #include "Mcp23008.h" 5 | 6 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == MCP23008 7 | 8 | #ifndef GPIO_MCP23008_I2C_ADDRESS 9 | #define GPIO_MCP23008_I2C_ADDRESS 0x20 10 | #endif 11 | 12 | // needs: https://github.com/adafruit/Adafruit-MCP23017-Arduino-Library and https://github.com/adafruit/Adafruit_BusIO 13 | #include "Adafruit_MCP23X08.h" 14 | Adafruit_MCP23X08 mcp; 15 | 16 | // check for MCP23008 device on the I2C bus 17 | bool GpioMcp23008::init() { 18 | static bool initialized = false; 19 | if (initialized) return found; 20 | 21 | if (mcp.begin_I2C(GPIO_MCP23008_I2C_ADDRESS, &HAL_WIRE)) { 22 | found = true; 23 | for (int i = 0; i < 8; i++) { mcp.pinMode(i, INPUT); } 24 | } else { found = false; DF("WRN: Gpio.init(), MCP23008 (I2C 0x"); if (DEBUG != OFF) SERIAL_DEBUG.print(GPIO_MCP23008_I2C_ADDRESS, HEX); DLF(") not found"); } 25 | HAL_WIRE_SET_CLOCK(); 26 | 27 | return found; 28 | } 29 | 30 | // set GPIO pin (0 to 7) mode for INPUT, INPUT_PULLUP, or OUTPUT 31 | void GpioMcp23008::pinMode(int pin, int mode) { 32 | if (found && pin >= 0 && pin <= 7) { 33 | #ifdef INPUT_PULLDOWN 34 | if (mode == INPUT_PULLDOWN) mode = INPUT; 35 | #endif 36 | mcp.pinMode(pin, mode); 37 | this->mode[pin] = mode; 38 | } 39 | } 40 | 41 | // one eight channel MCP23008 GPIO is supported, this gets the last set value 42 | int GpioMcp23008::digitalRead(int pin) { 43 | if (found && pin >= 0 && pin <= 7) { 44 | if (mode[pin] == INPUT || mode[pin] == INPUT_PULLUP) { 45 | return mcp.digitalRead(pin); 46 | } else return state[pin]; 47 | } else return 0; 48 | } 49 | 50 | // one eight channel MCP23008 GPIO is supported, this sets each output on or off 51 | void GpioMcp23008::digitalWrite(int pin, int value) { 52 | if (found && pin >= 0 && pin <= 7) { 53 | state[pin] = value; 54 | if (mode[pin] == OUTPUT) { 55 | mcp.digitalWrite(pin, value); 56 | } else { 57 | if (value == HIGH) pinMode(pin, INPUT_PULLUP); else pinMode(pin, INPUT); 58 | } 59 | } else return; 60 | } 61 | 62 | GpioMcp23008 gpio; 63 | 64 | #endif 65 | -------------------------------------------------------------------------------- /src/lib/gpioEx/mcp23008/Mcp23008.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C MCP23008 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == MCP23008 8 | 9 | class GpioMcp23008 : public Gpio { 10 | public: 11 | // scan for MCP23008 device 12 | bool init(); 13 | 14 | void pinMode(int pin, int mode); 15 | 16 | // one eight channel MCP23008 GPIO is supported, this gets the last set value 17 | int digitalRead(int pin); 18 | 19 | // one eight channel MCP23008 GPIO is supported, this sets each output on or off 20 | void digitalWrite(int pin, int value); 21 | 22 | private: 23 | bool found = false; 24 | 25 | int mode[8] = { INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT }; 26 | bool state[8] = { false, false, false, false, false, false, false, false }; 27 | }; 28 | 29 | extern GpioMcp23008 gpio; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/gpioEx/mcp23017/Mcp23017.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C MCP23017 GPIO support 3 | 4 | #include "Mcp23017.h" 5 | 6 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == MCP23017 7 | 8 | #ifndef GPIO_MCP23017_I2C_ADDRESS 9 | #define GPIO_MCP23017_I2C_ADDRESS 0x20 10 | #endif 11 | 12 | // needs: https://github.com/adafruit/Adafruit-MCP23017-Arduino-Library and https://github.com/adafruit/Adafruit_BusIO 13 | #include "Adafruit_MCP23X17.h" 14 | Adafruit_MCP23X17 mcp; 15 | 16 | // check for MCP23017 device on the I2C bus 17 | bool GpioMcp23017::init() { 18 | static bool initialized = false; 19 | if (initialized) return found; 20 | 21 | if (mcp.begin_I2C(GPIO_MCP23017_I2C_ADDRESS, &HAL_WIRE)) { 22 | found = true; 23 | for (int i = 0; i < 16; i++) { mcp.pinMode(i, INPUT); } 24 | } else { 25 | found = false; 26 | DF("WRN: Gpio.init(), MCP23017 (I2C 0x"); if (DEBUG != OFF) SERIAL_DEBUG.print(GPIO_MCP23017_I2C_ADDRESS, HEX); DLF(") not found"); 27 | } 28 | HAL_WIRE_SET_CLOCK(); 29 | 30 | return found; 31 | } 32 | 33 | // set GPIO pin (0 to 15) mode for INPUT, INPUT_PULLUP, or OUTPUT 34 | void GpioMcp23017::pinMode(int pin, int mode) { 35 | if (found && pin >= 0 && pin <= 15) { 36 | #ifdef INPUT_PULLDOWN 37 | if (mode == INPUT_PULLDOWN) mode = INPUT; 38 | #endif 39 | mcp.pinMode(pin, mode); 40 | this->mode[pin] = mode; 41 | } 42 | } 43 | 44 | // one sixteen channel MCP23017 GPIO is supported, this gets the last set value 45 | int GpioMcp23017::digitalRead(int pin) { 46 | if (found && pin >= 0 && pin <= 15) { 47 | if (mode[pin] == INPUT || mode[pin] == INPUT_PULLUP) { 48 | return mcp.digitalRead(pin); 49 | } else return state[pin]; 50 | } else return 0; 51 | } 52 | 53 | // one sixteen channel MCP23017 GPIO is supported, this sets each output on or off 54 | void GpioMcp23017::digitalWrite(int pin, int value) { 55 | if (found && pin >= 0 && pin <= 15) { 56 | state[pin] = value; 57 | if (mode[pin] == OUTPUT) { 58 | mcp.digitalWrite(pin, value); 59 | } else { 60 | if (value == HIGH) pinMode(pin, INPUT_PULLUP); else pinMode(pin, INPUT); 61 | } 62 | } else return; 63 | } 64 | 65 | GpioMcp23017 gpio; 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /src/lib/gpioEx/mcp23017/Mcp23017.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C MCP23017 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == MCP23017 8 | 9 | class GpioMcp23017 : public Gpio { 10 | public: 11 | // scan for MCP23017 device 12 | bool init(); 13 | 14 | void pinMode(int pin, int mode); 15 | 16 | // one sixteen channel MCP23017 GPIO is supported, this gets the last set value 17 | int digitalRead(int pin); 18 | 19 | // one sixteen channel MCP23017 GPIO is supported, this sets each output on or off 20 | void digitalWrite(int pin, int value); 21 | 22 | private: 23 | bool found = false; 24 | 25 | int mode[16] = { INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT }; 26 | bool state[16] = { false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false }; 27 | }; 28 | 29 | extern GpioMcp23017 gpio; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/gpioEx/pcf8574/Pcf8574.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C PCF8574 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == X8574 8 | 9 | #include // https://github.com/xreef/PCF8574_library/tree/master 10 | 11 | class GpioPcf8574 : public Gpio { 12 | public: 13 | // scan for PCF8575 device 14 | bool init(); 15 | 16 | void pinMode(int pin, int mode); 17 | 18 | // one sixteen channel PCF8575 GPIO is supported, this gets the last set value 19 | int digitalRead(int pin); 20 | 21 | // one sixteen channel PCF8575 GPIO is supported, this sets each output on or off 22 | void digitalWrite(int pin, int value); 23 | 24 | private: 25 | bool found = false; 26 | 27 | PCF8574 *pcf[4]; 28 | 29 | int mode[32]; 30 | bool state[32]; 31 | }; 32 | 33 | extern GpioPcf8574 gpio; 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /src/lib/gpioEx/pcf8575/Pcf8575.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C PCF8575 GPIO support 3 | 4 | #include "Pcf8575.h" 5 | 6 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == X8575 7 | 8 | #ifndef GPIO_PCF8575_I2C_ADDRESS 9 | #define GPIO_PCF8575_I2C_ADDRESS 0x20 10 | #endif 11 | 12 | #include // https://www.arduino.cc/reference/en/libraries/pcf8575/ 13 | 14 | PCF8575 pcf(GPIO_PCF8575_I2C_ADDRESS, &HAL_WIRE); // might need to change this I2C Address? 15 | 16 | // check for PCF8575 device on the I2C bus 17 | bool GpioPcf8575::init() { 18 | static bool initialized = false; 19 | if (initialized) return found; 20 | 21 | if (pcf.begin()) { 22 | found = true; 23 | } else { found = false; DF("WRN: Gpio.init(), PCF8575 (I2C 0x"); if (DEBUG != OFF) SERIAL_DEBUG.print(GPIO_PCF8575_I2C_ADDRESS, HEX); DLF(") not found"); } 24 | HAL_WIRE_SET_CLOCK(); 25 | 26 | return found; 27 | } 28 | 29 | // set GPIO pin (0 to 15) mode for INPUT, INPUT_PULLUP, or OUTPUT 30 | void GpioPcf8575::pinMode(int pin, int mode) { 31 | if (found && pin >= 0 && pin <= 15) { 32 | #ifdef INPUT_PULLDOWN 33 | if (mode == INPUT_PULLDOWN) mode = INPUT; 34 | #endif 35 | if (mode == INPUT_PULLUP) mode = INPUT; 36 | // no pinMode() seems to exist for the PCF8575, I assume reading sets input mode and writing sets output mode automatically 37 | this->mode[pin] = mode; 38 | } 39 | } 40 | 41 | // one sixteen channel Pcf8575 GPIO is supported, this gets the last set value 42 | int GpioPcf8575::digitalRead(int pin) { 43 | if (found && pin >= 0 && pin <= 15) { 44 | if (mode[pin] == INPUT || mode[pin] == INPUT_PULLUP) { 45 | return pcf.read(pin); 46 | } else return state[pin]; 47 | } else return 0; 48 | } 49 | 50 | // one sixteen channel Pcf8575 GPIO is supported, this sets each output on or off 51 | void GpioPcf8575::digitalWrite(int pin, int value) { 52 | if (found && pin >= 0 && pin <= 15) { 53 | state[pin] = value; 54 | if (mode[pin] == OUTPUT) { 55 | pcf.write(pin, value); 56 | } else { 57 | if (value == HIGH) pinMode(pin, INPUT_PULLUP); else pinMode(pin, INPUT); 58 | } 59 | } else return; 60 | } 61 | 62 | GpioPcf8575 gpio; 63 | 64 | #endif 65 | -------------------------------------------------------------------------------- /src/lib/gpioEx/pcf8575/Pcf8575.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C PCF8575 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == X8575 8 | 9 | class GpioPcf8575 : public Gpio { 10 | public: 11 | // scan for PCF8575 device 12 | bool init(); 13 | 14 | void pinMode(int pin, int mode); 15 | 16 | // one sixteen channel PCF8575 GPIO is supported, this gets the last set value 17 | int digitalRead(int pin); 18 | 19 | // one sixteen channel PCF8575 GPIO is supported, this sets each output on or off 20 | void digitalWrite(int pin, int value); 21 | 22 | private: 23 | bool found = false; 24 | 25 | int mode[16] = { INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT }; 26 | bool state[16] = { false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false }; 27 | }; 28 | 29 | extern GpioPcf8575 gpio; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/gpioEx/ssr74HC595/Ssr74HC595.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // 74HC595 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == SSR74HC595 8 | 9 | class GpioSsr74HC595 : public Gpio { 10 | public: 11 | // init for SSR74HC595 device 12 | bool init(); 13 | 14 | // set GPIO pin mode for INPUT, INPUT_PULLUP, or OUTPUT (input does nothing always, false) 15 | void pinMode(int pin, int mode); 16 | 17 | // up to four eight channel 74HC595 GPIOs are supported, this gets the last set value (output only) 18 | int digitalRead(int pin); 19 | 20 | // up to four eight channel 74HC595 GPIOs are supported, this sets each output on or off 21 | void digitalWrite(int pin, int value); 22 | 23 | private: 24 | uint32_t register_value = 0; 25 | bool found = false; 26 | 27 | int mode[32]; 28 | bool state[32]; 29 | }; 30 | 31 | extern GpioSsr74HC595 gpio; 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /src/lib/gpioEx/sws/Sws.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Smart Web Server GPIO support (optional when SWS Encoders are not used) 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == SWS 8 | 9 | #include "../../commands/CommandErrors.h" 10 | 11 | class GpioSws : public Gpio { 12 | public: 13 | // scan for SWS device 14 | bool init(); 15 | 16 | // process any gpio commands 17 | bool command(char *reply, char *command, char *parameter, bool *supressFrame, bool *numericReply, CommandError *commandError); 18 | 19 | void pinMode(int pin, int mode); 20 | 21 | // one eight channel SWS GPIO is supported, this gets the last set value 22 | int digitalRead(int pin); 23 | 24 | // one eight channel SWS GPIO is supported, this sets each output on or off 25 | void digitalWrite(int pin, int value); 26 | 27 | // one eight channel SWS GPIO is supported 28 | void analogWrite(int pin, int value); 29 | 30 | // monitor SWS presence 31 | void poll(); 32 | 33 | private: 34 | 35 | bool found = false; 36 | bool active = false; 37 | bool readyStage1 = false; 38 | bool readyStage2 = false; 39 | unsigned long startTimeMs = 0; 40 | unsigned long lastActiveTimeMs = 0; 41 | 42 | bool virtualRead[8] = {false, false, false, false, false, false, false, false}; 43 | int virtualWrite[8] = {false, false, false, false, false, false, false, false}; 44 | char virtualMode[8] = {'X', 'X', 'X', 'X', 'X', 'X', 'X', 'X' }; 45 | 46 | int mode[8] = {OFF, OFF, OFF, OFF, OFF, OFF, OFF, OFF}; 47 | int state[8] = {false, false, false, false, false, false, false, false}; 48 | }; 49 | 50 | extern GpioSws gpio; 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /src/lib/gpioEx/tca9555/Tca9555.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C TCA9555 GPIO support 3 | 4 | #include "Tca9555.h" 5 | 6 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == X9555 7 | 8 | #ifndef GPIO_TCA9555_I2C_ADDRESS 9 | #define GPIO_TCA9555_I2C_ADDRESS 0x27 10 | #endif 11 | 12 | #include // https://www.arduino.cc/reference/en/libraries/tca9555/ 13 | 14 | TCA9555 tca(GPIO_TCA9555_I2C_ADDRESS, &HAL_WIRE); // might need to change this I2C Address? 15 | 16 | // check for TCA9555 device on the I2C bus 17 | bool GpioTca9555::init() { 18 | static bool initialized = false; 19 | if (initialized) return found; 20 | 21 | if (tca.begin()) { 22 | found = true; 23 | for (int i = 0; i < 16; i++) { tca.pinMode1(i, INPUT); } 24 | } else { found = false; DLF("WRN: Gpio.init(), TCA9555 (I2C 0x"); if (DEBUG != OFF) SERIAL_DEBUG.print(GPIO_TCA9555_I2C_ADDRESS, HEX); DLF(") not found"); } 25 | HAL_WIRE_SET_CLOCK(); 26 | 27 | return found; 28 | } 29 | 30 | // set GPIO pin (0 to 15) mode for INPUT, INPUT_PULLUP, or OUTPUT 31 | void GpioTca9555::pinMode(int pin, int mode) { 32 | if (found && pin >= 0 && pin <= 15) { 33 | #ifdef INPUT_PULLDOWN 34 | if (mode == INPUT_PULLDOWN) mode = INPUT; 35 | #endif 36 | if (mode == INPUT_PULLUP) mode = INPUT; 37 | tca.pinMode1(pin, mode); 38 | this->mode[pin] = mode; 39 | } 40 | } 41 | 42 | // one sixteen channel Tca9555 GPIO is supported, this gets the last set value 43 | int GpioTca9555::digitalRead(int pin) { 44 | if (found && pin >= 0 && pin <= 15) { 45 | if (mode[pin] == INPUT || mode[pin] == INPUT_PULLUP) { 46 | return tca.read1(pin); 47 | } else return state[pin]; 48 | } else return 0; 49 | } 50 | 51 | // one sixteen channel Tca9555 GPIO is supported, this sets each output on or off 52 | void GpioTca9555::digitalWrite(int pin, int value) { 53 | if (found && pin >= 0 && pin <= 15) { 54 | state[pin] = value; 55 | if (mode[pin] == OUTPUT) { 56 | tca.write1(pin, value); 57 | } else { 58 | if (value == HIGH) tca.pinMode1(pin, INPUT_PULLUP); else tca.pinMode1(pin, INPUT); 59 | } 60 | } else return; 61 | } 62 | 63 | GpioTca9555 gpio; 64 | 65 | #endif 66 | -------------------------------------------------------------------------------- /src/lib/gpioEx/tca9555/Tca9555.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // I2C TCA9555 GPIO support 3 | #pragma once 4 | 5 | #include "../GpioBase.h" 6 | 7 | #if defined(GPIO_DEVICE) && GPIO_DEVICE == X9555 8 | 9 | class GpioTca9555 : public Gpio { 10 | public: 11 | // scan for TCA9555 device 12 | bool init(); 13 | 14 | void pinMode(int pin, int mode); 15 | 16 | // one sixteen channel TCA9555 GPIO is supported, this gets the last set value 17 | int digitalRead(int pin); 18 | 19 | // one sixteen channel TCA9555 GPIO is supported, this sets each output on or off 20 | void digitalWrite(int pin, int value); 21 | 22 | private: 23 | bool found = false; 24 | 25 | int mode[16] = { INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT, INPUT }; 26 | bool state[16] = { false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false }; 27 | }; 28 | 29 | extern GpioTca9555 gpio; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/nv/24xx/24XX.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (for 24XX series I2C EEPROMS) 3 | 4 | #pragma once 5 | 6 | #include "../NvBase.h" 7 | 8 | #if defined(NV_DRIVER) && (NV_DRIVER == NV_2416 || NV_DRIVER == NV_2432 || NV_DRIVER == NV_AT24C32 || NV_DRIVER == NV_2464 || NV_DRIVER == NV_24128 || NV_DRIVER == NV_24256) 9 | 10 | class NonVolatileStorage24XX : public NonVolatileStorage { 11 | public: 12 | // prepare FLASH based EEPROM emulation for operation 13 | // E2END: NV size in bytes - 1 14 | // NV_CACHED: true to enable the cache (note NV size must be divisible by 8 if enabled) 15 | // NV_WAIT: minimum time in milliseconds to wait (after last write) before writing cache or doing the commit 16 | // HAL_WIRE: I2C interface pointer 17 | // NV_I2C_ADDRESS: I2C address 18 | // result: true if the device was found, or false if not 19 | bool init(); 20 | 21 | private: 22 | // returns false if ready to read or write immediately 23 | bool busy(); 24 | 25 | // read byte at position i from storage 26 | uint8_t readFromStorage(uint16_t i); 27 | 28 | // write value j to position i in storage 29 | void writeToStorage(uint16_t i, uint8_t j); 30 | 31 | // write value j of count bytes to position starting at i in storage 32 | // these writes must be aligned with the page size! 33 | void writePageToStorage(uint16_t i, uint8_t *j, uint8_t count); 34 | 35 | TwoWire* wire; 36 | uint8_t eepromAddress = 0; 37 | uint32_t nextOpMs = 0; 38 | }; 39 | 40 | extern NonVolatileStorage24XX nv; 41 | 42 | #endif 43 | -------------------------------------------------------------------------------- /src/lib/nv/Nv.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage base class 3 | 4 | #if NV_DRIVER == NV_EEPROM 5 | #include "eeprom/EEPROM.h" 6 | 7 | #elif NV_DRIVER == NV_ESP 8 | #include "esp/Esp.h" 9 | 10 | #elif NV_DRIVER == NV_M0 11 | #include "m0/M0.h" 12 | 13 | #elif NV_DRIVER == NV_2416 || NV_DRIVER == NV_2432 || NV_DRIVER == NV_AT24C32 || NV_DRIVER == NV_2464 || NV_DRIVER == NV_24128 || NV_DRIVER == NV_24256 14 | #include "24xx/24XX.h" 15 | 16 | #elif NV_DRIVER == NV_MB85RC32 || NV_DRIVER == NV_MB85RC64 || NV_DRIVER == NV_MB85RC256 17 | #include "mb85rc/MB85RC.h" 18 | 19 | #endif 20 | -------------------------------------------------------------------------------- /src/lib/nv/eeprom/EEPROM.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in) 3 | 4 | #include "EEPROM.h" 5 | 6 | #if defined(NV_DRIVER) && NV_DRIVER == NV_EEPROM 7 | 8 | // bring in the EEPROM library here if this is an Mega2560, etc. 9 | #ifdef __AVR__ 10 | #include 11 | #endif 12 | 13 | bool NonVolatileStorageEEPROM::init() { 14 | // setup size, cache, etc. 15 | return NonVolatileStorage::init(E2END + 1, NV_CACHED, NV_WAIT, false); 16 | } 17 | 18 | uint8_t NonVolatileStorageEEPROM::readFromStorage(uint16_t i) { 19 | return EEPROM.read(i); 20 | } 21 | 22 | void NonVolatileStorageEEPROM::writeToStorage(uint16_t i, uint8_t j) { 23 | EEPROM.write(i, j); 24 | } 25 | 26 | NonVolatileStorageEEPROM nv; 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /src/lib/nv/eeprom/EEPROM.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in) 3 | 4 | #pragma once 5 | 6 | #include "../../../Common.h" 7 | 8 | #if defined(NV_DRIVER) && NV_DRIVER == NV_EEPROM 9 | 10 | // don't bring in the EEPROM library here if this is an Mega2560, etc. 11 | #ifndef __AVR__ 12 | #include 13 | #endif 14 | 15 | #include "../NvBase.h" 16 | 17 | class NonVolatileStorageEEPROM : public NonVolatileStorage { 18 | public: 19 | // prepare FLASH based EEPROM emulation for operation 20 | // E2END: NV size in bytes - 1 21 | // NV_CACHED: true to enable the cache (note NV size must be divisible by 8 if enabled) 22 | // NV_WAIT: minimum time in milliseconds to wait (after last write) before writing cache or doing the commit 23 | // result: true if the device was found, or false if not 24 | bool init(); 25 | 26 | private: 27 | // read byte at position i from storage 28 | uint8_t readFromStorage(uint16_t i); 29 | 30 | // write value j to position i in storage 31 | void writeToStorage(uint16_t i, uint8_t j); 32 | }; 33 | 34 | extern NonVolatileStorageEEPROM nv; 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /src/lib/nv/esp/Esp.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in, flash emulation ESP8266/ESP32) 3 | 4 | #include "Esp.h" 5 | 6 | #if defined(NV_DRIVER) && NV_DRIVER == NV_ESP 7 | 8 | // from the NV library 9 | #if defined(ESP32) 10 | extern void timerAlarmsDisable(); 11 | extern void timerAlarmsEnable(); 12 | #endif 13 | 14 | bool NonVolatileStorageESP::init() { 15 | if (E2END + 1 > 4096 || NV_WAIT == 0) return false; 16 | 17 | // setup size, cache, etc. 18 | if (!NonVolatileStorage::init(E2END + 1, NV_CACHED, NV_WAIT, false)) return false; 19 | 20 | EEPROM.begin(E2END + 1); 21 | 22 | return true; 23 | } 24 | 25 | void NonVolatileStorageESP::poll(bool disableInterrupts) { 26 | if (dirty && ((long)(millis() - commitReadyTimeMs) >= 0)) { 27 | #if defined(ESP32) 28 | if (disableInterrupts) timerAlarmsDisable(); 29 | #endif 30 | EEPROM.commit(); 31 | #if defined(ESP32) 32 | if (disableInterrupts) timerAlarmsEnable(); 33 | #endif 34 | dirty = false; 35 | } 36 | #if !defined(ESP32) 37 | // stop compiler warnings 38 | (void)(disableInterrupts); 39 | #endif 40 | } 41 | 42 | bool NonVolatileStorageESP::committed() { 43 | return !dirty; 44 | } 45 | 46 | uint8_t NonVolatileStorageESP::readFromStorage(uint16_t i) { 47 | return EEPROM.read(i); 48 | } 49 | 50 | void NonVolatileStorageESP::writeToStorage(uint16_t i, uint8_t j) { 51 | EEPROM.write(i, j); 52 | dirty = true; 53 | } 54 | 55 | NonVolatileStorageESP nv; 56 | 57 | #endif 58 | -------------------------------------------------------------------------------- /src/lib/nv/esp/Esp.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in, flash emulation ESP32) 3 | 4 | #pragma once 5 | 6 | #include "../NvBase.h" 7 | 8 | #if defined(NV_DRIVER) && NV_DRIVER == NV_ESP 9 | 10 | #include 11 | 12 | class NonVolatileStorageESP : public NonVolatileStorage { 13 | public: 14 | // prepare FLASH based EEPROM emulation for operation 15 | // E2END: NV size in bytes - 1 16 | // NV_CACHED: true to enable the cache (note NV size must be divisible by 8 if enabled) 17 | // NV_WAIT: minimum time in milliseconds to wait (after last write) before writing cache or doing the commit 18 | // result: true if the device was found, or false if not 19 | bool init(); 20 | 21 | // call frequently to perform any operations that need to happen in the background 22 | void poll(bool disableInterrupts = true); 23 | 24 | // returns true if all data in any cache has been written 25 | bool committed(); 26 | 27 | private: 28 | // read byte at position i from storage 29 | uint8_t readFromStorage(uint16_t i); 30 | 31 | // write value j to position i in storage 32 | void writeToStorage(uint16_t i, uint8_t j); 33 | 34 | bool dirty = false; 35 | }; 36 | 37 | extern NonVolatileStorageESP nv; 38 | 39 | #endif -------------------------------------------------------------------------------- /src/lib/nv/m0/M0.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in, flash emulation for Arduino M0) 3 | 4 | #include "M0.h" 5 | 6 | #if defined(NV_DRIVER) && NV_DRIVER == NV_M0 7 | 8 | bool NonVolatileStorageM0::init(uint16_t size, bool cacheEnable, uint16_t wait, bool checkEnable, TwoWire* wire, uint8_t address) { 9 | if (E2END + 1 != 1024 || wait == false) return false; 10 | 11 | // setup size, cache, etc. 12 | NonVolatileStorage::init(E2END + 1, NV_CACHED, NV_WAIT, false); 13 | 14 | return true; 15 | } 16 | 17 | void NonVolatileStorageM0::poll(bool disableInterrupts) { 18 | if (dirty && ((long)(millis() - commitReadyTimeMs) >= 0)) { 19 | EEPROM.commit(); 20 | dirty = false; 21 | } 22 | // stop compiler warnings 23 | (void)(disableInterrupts); 24 | } 25 | 26 | bool NonVolatileStorageM0::committed() { 27 | return !dirty; 28 | } 29 | 30 | uint8_t NonVolatileStorageM0::readFromStorage(uint16_t i) { 31 | return EEPROM.read(i); 32 | } 33 | 34 | void NonVolatileStorageM0::writeToStorage(uint16_t i, uint8_t j) { 35 | EEPROM.write(i, j); 36 | dirty = true; 37 | } 38 | 39 | NonVolatileStorageM0 nv; 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /src/lib/nv/m0/M0.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (default/built-in, flash emulation M0) 3 | 4 | #pragma once 5 | 6 | #include "../NvBase.h" 7 | 8 | #if defined(NV_DRIVER) && NV_DRIVER == NV_M0 9 | 10 | #include "FlashAsEEPROM.h" // https://github.com/cmaglie/FlashStorage 11 | 12 | class NonVolatileStorageM0 : public NonVolatileStorage { 13 | public: 14 | // prepare FLASH based EEPROM emulation for operation 15 | // E2END: NV size in bytes - 1 16 | // NV_CACHED: true to enable the cache (note NV size must be divisible by 8 if enabled) 17 | // NV_WAIT: minimum time in milliseconds to wait (after last write) before writing cache or doing the commit 18 | // result: true if the device was found, or false if not 19 | bool init(uint16_t size, bool cacheEnable, uint16_t wait, bool checkEnable, TwoWire* wire = NULL, uint8_t address = 0); 20 | 21 | // call frequently to perform any operations that need to happen in the background 22 | void poll(bool disableInterrupts = true); 23 | 24 | // returns true if all data in any cache has been written 25 | bool committed(); 26 | 27 | private: 28 | // read byte at position i from storage 29 | uint8_t readFromStorage(uint16_t i); 30 | 31 | // write value j to position i in storage 32 | void writeToStorage(uint16_t i, uint8_t j); 33 | 34 | bool dirty = false; 35 | }; 36 | 37 | extern NonVolatileStorageM0 nv; 38 | 39 | #endif -------------------------------------------------------------------------------- /src/lib/nv/mb85rc/MB85RC.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (caching, for 85RC series I2C FRAMS) 3 | 4 | #include "MB85RC.h" 5 | 6 | #if defined(NV_DRIVER) && (NV_DRIVER == NV_MB85RC32 || NV_DRIVER == NV_MB85RC64 || NV_DRIVER == NV_MB85RC256) 7 | 8 | #define MSB(i) (i >> 8) 9 | #define LSB(i) (i & 0xFF) 10 | 11 | // no wait needed for 85RC series 12 | #ifndef FRAM_WRITE_WAIT 13 | #define FRAM_WRITE_WAIT 0 14 | #endif 15 | 16 | bool NonVolatileStorageMB85RC::init() { 17 | // setup size, cache, etc. 18 | if (!NonVolatileStorage::init(E2END + 1, NV_CACHED, NV_WAIT, false)) return false; 19 | 20 | this->wire = &HAL_WIRE; 21 | framAddress = NV_I2C_ADDRESS; 22 | wire->begin(); 23 | 24 | wire->beginTransmission(framAddress); 25 | bool error = wire->endTransmission(); 26 | return !error; 27 | } 28 | 29 | bool NonVolatileStorageMB85RC::busy() { 30 | return (int32_t)(millis() - nextOpMs) < 0; 31 | // posssibly a better way? 32 | // wire->beginTransmission(framAddress); 33 | // return wire->endTransmission() == 0; 34 | } 35 | 36 | uint8_t NonVolatileStorageMB85RC::readFromStorage(uint16_t i) { 37 | while (busy()) {} 38 | 39 | wire->beginTransmission(framAddress); 40 | wire->write(MSB(i)); 41 | wire->write(LSB(i)); 42 | wire->endTransmission(); 43 | 44 | size_t result = wire->requestFrom(framAddress, (uint8_t)1); 45 | if (result != 1) return 0; 46 | 47 | return wire->read(); 48 | } 49 | 50 | void NonVolatileStorageMB85RC::writeToStorage(uint16_t i, uint8_t j) { 51 | while (busy()) {} 52 | 53 | wire->beginTransmission(framAddress); 54 | wire->write(MSB(i)); 55 | wire->write(LSB(i)); 56 | wire->write(j); 57 | wire->endTransmission(); 58 | nextOpMs = millis() + FRAM_WRITE_WAIT; 59 | } 60 | 61 | NonVolatileStorageMB85RC nv; 62 | 63 | #endif 64 | -------------------------------------------------------------------------------- /src/lib/nv/mb85rc/MB85RC.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // non-volatile storage (caching, for 85RC series I2C FRAMS) 3 | 4 | #pragma once 5 | 6 | #include "../NvBase.h" 7 | 8 | #if defined(NV_DRIVER) && (NV_DRIVER == NV_MB85RC32 || NV_DRIVER == NV_MB85RC64 || NV_DRIVER == NV_MB85RC256) 9 | 10 | class NonVolatileStorageMB85RC : public NonVolatileStorage { 11 | public: 12 | // prepare FLASH based EEPROM emulation for operation 13 | // E2END: NV size in bytes - 1 14 | // NV_CACHED: true to enable the cache (note NV size must be divisible by 8 if enabled) 15 | // NV_WAIT: minimum time in milliseconds to wait (after last write) before writing cache or doing the commit 16 | // HAL_WIRE: I2C interface pointer 17 | // NV_I2C_ADDRESS: I2C address 18 | // result: true if the device was found, or false if not 19 | bool init(); 20 | 21 | private: 22 | // returns false if ready to read or write immediately 23 | bool busy(); 24 | 25 | // read byte at position i from storage 26 | uint8_t readFromStorage(uint16_t i); 27 | 28 | // write value j to position i in storage 29 | void writeToStorage(uint16_t i, uint8_t j); 30 | 31 | TwoWire* wire; 32 | uint8_t framAddress = 0; 33 | uint32_t nextOpMs = 0; 34 | }; 35 | 36 | extern NonVolatileStorageMB85RC nv; 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /src/lib/pushButton/PushButton.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------------------- 2 | // Handle push buttons 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | // threshold in milliseconds (for tone detection, 40ms/7 = +/-17.5%) 8 | #define TONE_FREQ_THRESHOLD 7.0 9 | 10 | class Button { 11 | public: 12 | // create object 13 | // \param pin MCU pin 14 | // \param initState initialization state: INPUT, INPUT_PULLUP, or INPUT_PULLDOWN 15 | // \param trigger triggered state: HIGH or LOW, optional 16 | // analog threshold/hysteresis |THLD(t) |HIST(h) are 10 bit values 17 | Button(int pin, int initState, int32_t trigger); 18 | 19 | // must be repeatedly called to check status of button 20 | void poll(); 21 | 22 | // is the button down 23 | bool isDown(); 24 | 25 | // was the button down since last checked 26 | bool wasPressed(bool peek = false); 27 | 28 | // was the button down since last checked 29 | bool wasDoublePressed(bool peek = false); 30 | 31 | // was the button down since last checked 32 | bool wasClicked(bool peek = false); 33 | 34 | // clear pressed state 35 | void clearPress(); 36 | 37 | // is the button up 38 | bool isUp(); 39 | 40 | // number of ms down 41 | long timeDown(); 42 | 43 | // number of ms up 44 | long timeUp(); 45 | 46 | // check to see if this button has the SHC tone (12.5 Hz nominal) 47 | bool hasTone(); 48 | 49 | // in Hz (0.05 to 5000Hz range) returns NAN otherwise 50 | double toneFreq(); 51 | 52 | private: 53 | int pin; 54 | int state = HIGH; 55 | int lastStableState = HIGH; 56 | int threshold; 57 | int hysteresis; 58 | unsigned long debounceMs = 0; 59 | unsigned long stableStartMs = 0; 60 | unsigned long stableMs = 0; 61 | bool isAnalog = false; 62 | bool pressed = false; 63 | bool doublePressed = false; 64 | double avgPulseDuration = 2000.0; 65 | int UP = HIGH; 66 | int DOWN = LOW; 67 | }; 68 | -------------------------------------------------------------------------------- /src/lib/serial/Serial_IP_Ethernet.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Polling serial IP for Ethernet 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | #include "../ethernet/EthernetManager.h" 7 | 8 | #if OPERATIONAL_MODE >= ETHERNET_FIRST && OPERATIONAL_MODE <= ETHERNET_LAST && SERIAL_SERVER != OFF 9 | 10 | #ifdef ESP8266 11 | #ifndef ETHERNET_W5500 12 | #error "The ESP8266 Ethernet option supports the W5500 only" 13 | #endif 14 | #include // https://github.com/adafruit/Ethernet2 15 | #else 16 | #if OPERATIONAL_MODE == ETHERNET_TEENSY41 17 | #include 18 | #else 19 | #include // built-in library or my https://github.com/hjd1964/Ethernet for ESP32 and ASCOM Alpaca support 20 | #endif 21 | #endif 22 | 23 | class IPSerial : public Stream { 24 | public: 25 | void begin(long port, unsigned long clientTimeoutMs = 2000, bool persist = false); 26 | void restart(); 27 | void end(); 28 | 29 | void flush(void); 30 | int available(void); 31 | int peek(void); 32 | int read(void); 33 | size_t write(uint8_t data); 34 | size_t write(const uint8_t* data, size_t count); 35 | inline size_t write(unsigned long n) { return write((uint8_t)n); } 36 | inline size_t write(long n) { return write((uint8_t)n); } 37 | inline size_t write(unsigned int n) { return write((uint8_t)n); } 38 | inline size_t write(int n) { return write((uint8_t)n); } 39 | 40 | using Print::write; 41 | 42 | private: 43 | EthernetServer *cmdSvr; 44 | EthernetClient cmdSvrClient; 45 | 46 | int port = -1; 47 | unsigned long clientTimeoutMs; 48 | unsigned long clientEndTimeMs = 0; 49 | bool active = false; 50 | bool persist = false; 51 | }; 52 | 53 | #if SERIAL_SERVER == STANDARD || SERIAL_SERVER == BOTH 54 | extern IPSerial SerialIP; 55 | #define SERIAL_SIP SerialIP 56 | #endif 57 | 58 | #if SERIAL_SERVER == PERSISTENT || SERIAL_SERVER == BOTH 59 | extern IPSerial SerialPIP1; 60 | #define SERIAL_PIP1 SerialPIP1 61 | #endif 62 | 63 | #endif 64 | -------------------------------------------------------------------------------- /src/lib/serial/Serial_IP_Ethernet_Client.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Polling serial IP for Ethernet 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | #include "../ethernet/EthernetManager.h" 7 | 8 | #if OPERATIONAL_MODE >= ETHERNET_FIRST && OPERATIONAL_MODE <= ETHERNET_LAST && SERIAL_CLIENT != OFF 9 | 10 | #ifdef ESP8266 11 | #ifndef ETHERNET_W5500 12 | #error "The ESP8266 Ethernet option supports the W5500 only" 13 | #endif 14 | #include // https://github.com/adafruit/Ethernet2 15 | #else 16 | #if OPERATIONAL_MODE == ETHERNET_TEENSY41 17 | #include 18 | #else 19 | #include // built-in library or my https://github.com/hjd1964/Ethernet for ESP32 and ASCOM Alpaca support 20 | #endif 21 | #endif 22 | 23 | class IPSerialClient : public Stream { 24 | public: 25 | bool begin(long port, unsigned long clientTimeoutMs = 2000, bool persist = false); 26 | void end(); 27 | bool isConnected(); 28 | 29 | void flush(void); 30 | int available(void); 31 | int peek(void); 32 | int read(void); 33 | int availableForWrite() { return 1; } 34 | size_t write(uint8_t data); 35 | size_t write(const uint8_t* data, size_t count); 36 | inline size_t write(unsigned long n) { return write((uint8_t)n); } 37 | inline size_t write(long n) { return write((uint8_t)n); } 38 | inline size_t write(unsigned int n) { return write((uint8_t)n); } 39 | inline size_t write(int n) { return write((uint8_t)n); } 40 | 41 | using Print::write; 42 | 43 | void poll(); 44 | 45 | private: 46 | EthernetClient cmdSvrClient; 47 | IPAddress onStep; 48 | 49 | int port = -1; 50 | unsigned long lastActivityTimeMs = 0; 51 | unsigned long clientTimeoutMs; 52 | unsigned long clientEndTimeMs = 0; 53 | bool active = false; 54 | bool persist = false; 55 | }; 56 | 57 | extern IPSerialClient SerialIPClient; 58 | #define SERIAL_IP SerialIPClient 59 | 60 | #endif 61 | -------------------------------------------------------------------------------- /src/lib/serial/Serial_IP_Wifi.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Polling serial IP for ESP32 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | #include "../wifi/WifiManager.h" 7 | 8 | #if OPERATIONAL_MODE == WIFI && SERIAL_SERVER != OFF 9 | 10 | #if defined(ESP32) 11 | #include 12 | #include 13 | #include 14 | #elif defined(ESP8266) 15 | #include 16 | #include 17 | #include 18 | #else 19 | #error "Configuration (Config.h): No Wifi support is present for this device" 20 | #endif 21 | 22 | class IPSerial : public Stream { 23 | public: 24 | void begin(long port, unsigned long clientTimeoutMs = 2000, bool persist = false); 25 | void end(); 26 | 27 | void flush(void); 28 | int available(void); 29 | int peek(void); 30 | int read(void); 31 | size_t write(uint8_t data); 32 | size_t write(const uint8_t* data, size_t count); 33 | inline size_t write(unsigned long n) { return write((uint8_t)n); } 34 | inline size_t write(long n) { return write((uint8_t)n); } 35 | inline size_t write(unsigned int n) { return write((uint8_t)n); } 36 | inline size_t write(int n) { return write((uint8_t)n); } 37 | 38 | using Print::write; 39 | 40 | private: 41 | WiFiServer *cmdSvr; 42 | WiFiClient cmdSvrClient; 43 | 44 | int port = -1; 45 | unsigned long clientTimeoutMs; 46 | unsigned long clientEndTimeMs = 0; 47 | bool active = false; 48 | bool persist = false; 49 | }; 50 | 51 | #if SERIAL_SERVER == STANDARD || SERIAL_SERVER == BOTH 52 | extern IPSerial SerialIP; 53 | #define SERIAL_SIP SerialIP 54 | #endif 55 | 56 | #if SERIAL_SERVER == PERSISTENT || SERIAL_SERVER == BOTH 57 | extern IPSerial SerialPIP1; 58 | extern IPSerial SerialPIP2; 59 | extern IPSerial SerialPIP3; 60 | #define SERIAL_PIP1 SerialPIP1 61 | #define SERIAL_PIP2 SerialPIP2 62 | #define SERIAL_PIP3 SerialPIP3 63 | #endif 64 | 65 | #endif 66 | -------------------------------------------------------------------------------- /src/lib/serial/Serial_IP_Wifi_Client.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // IP communication routines 3 | 4 | // original work by jesco-t 5 | 6 | #pragma once 7 | 8 | #include "../../Common.h" 9 | #include "../wifi/WifiManager.h" 10 | 11 | #if OPERATIONAL_MODE == WIFI && SERIAL_CLIENT == ON 12 | 13 | #if defined(ESP32) 14 | #include 15 | #include 16 | #include 17 | #elif defined(ESP8266) 18 | #include 19 | #include 20 | #include 21 | #else 22 | #error "Configuration (Config.h): No Wifi support is present for this device" 23 | #endif 24 | 25 | class IPSerialClient : public Stream { 26 | public: 27 | bool begin(long port, unsigned long clientTimeoutMs = 2000, bool persist = false); 28 | void end(); 29 | bool isConnected(); 30 | 31 | void flush(void); 32 | int available(void); 33 | int peek(void); 34 | int read(void); 35 | int availableForWrite() { return 1; } 36 | size_t write(uint8_t data); 37 | size_t write(const uint8_t* data, size_t count); 38 | inline size_t write(unsigned long n) { return write((uint8_t)n); } 39 | inline size_t write(long n) { return write((uint8_t)n); } 40 | inline size_t write(unsigned int n) { return write((uint8_t)n); } 41 | inline size_t write(int n) { return write((uint8_t)n); } 42 | 43 | using Print::write; 44 | 45 | void poll(); 46 | 47 | private: 48 | WiFiClient cmdSvrClient; 49 | IPAddress onStep; 50 | 51 | int port = -1; 52 | unsigned long lastActivityTimeMs = 0; 53 | unsigned long clientTimeoutMs; 54 | bool active = false; 55 | bool persist = false; 56 | }; 57 | 58 | extern IPSerialClient SerialIPClient; 59 | #define SERIAL_IP SerialIPClient 60 | #endif -------------------------------------------------------------------------------- /src/lib/serial/Serial_Local.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Local Serial for sending internal commands 3 | 4 | #include "Serial_Local.h" 5 | 6 | #if defined(SERIAL_LOCAL_MODE) && SERIAL_LOCAL_MODE == ON 7 | 8 | void SerialLocal::begin(long baud) { 9 | // init the buffers 10 | xmit_index = 0; 11 | xmit_buffer[0] = 0; 12 | recv_head = 0; 13 | recv_tail = 0; 14 | recv_buffer[0] = 0; 15 | (void)(baud); 16 | 17 | #ifdef ESP32 18 | mutex = xSemaphoreCreateMutex(); 19 | #endif 20 | } 21 | 22 | void SerialLocal::end() { } 23 | 24 | void SerialLocal::transmit(const char *data) { 25 | #ifdef ESP32 26 | xSemaphoreTake(mutex, portMAX_DELAY); 27 | #endif 28 | 29 | int data_len = strlen(data); 30 | for (int i = 0; i < data_len; i++) { 31 | recv_buffer[recv_tail] = data[i]; 32 | recv_tail++; 33 | } 34 | 35 | #ifdef ESP32 36 | xSemaphoreGive(mutex); 37 | #endif 38 | } 39 | 40 | char *SerialLocal::receive() { 41 | #ifdef ESP32 42 | xSemaphoreTake(mutex, portMAX_DELAY); 43 | #endif 44 | 45 | int i = 0; 46 | xmit_result[i] = 0; 47 | while (xmit_buffer[xmit_index] != 0) { 48 | xmit_result[i++] = xmit_buffer[xmit_index++]; 49 | xmit_index &= 0b1111111; 50 | } 51 | xmit_result[i] = 0; 52 | 53 | #ifdef ESP32 54 | xSemaphoreGive(mutex); 55 | #endif 56 | return xmit_result; 57 | } 58 | 59 | int SerialLocal::read(void) { 60 | if (!available()) return -1; 61 | 62 | #ifdef ESP32 63 | xSemaphoreTake(mutex, portMAX_DELAY); 64 | #endif 65 | 66 | recv_buffer[recv_tail] = 0; 67 | char c = recv_buffer[recv_head]; 68 | if (c) recv_head++; 69 | 70 | #ifdef ESP32 71 | xSemaphoreGive(mutex); 72 | #endif 73 | return c; 74 | } 75 | 76 | SerialLocal serialLocal; 77 | 78 | #endif 79 | -------------------------------------------------------------------------------- /src/lib/softSpi/Pins.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Step driver mode control pins 3 | #pragma once 4 | 5 | #include 6 | -------------------------------------------------------------------------------- /src/lib/softSpi/SoftSpi.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Simple software SPI routines (CPOL=1, CPHA=1) just for TMC stepper drivers 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | class SoftSpi { 8 | public: 9 | // check pins and report status 10 | bool init(int16_t mosi, int16_t sck, int16_t cs, int16_t miso); 11 | // setup pins and activate CS 12 | void begin(); 13 | // cycle CS to reset conversation 14 | void pause(); 15 | // set CS high to disable conversation 16 | void end(); 17 | // send/receive an 8 bit value 18 | uint8_t transfer(uint8_t data_out); 19 | // send/receive an 32 bit value 20 | uint32_t transfer32(uint32_t data_out); 21 | // returns true if this interface only supports sending data 22 | bool outOnly() { return miso == OFF; } 23 | 24 | private: 25 | int16_t miso, mosi, sck, cs; 26 | }; 27 | -------------------------------------------------------------------------------- /src/lib/sound/Sound.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------------------- 2 | // Sound 3 | 4 | #include "Sound.h" 5 | 6 | #ifdef STATUS_BUZZER 7 | 8 | #include "../tasks/OnTask.h" 9 | #include "../gpioEx/GpioEx.h" 10 | 11 | void Sound::init() { 12 | #if STATUS_BUZZER == ON 13 | pinModeEx(STATUS_BUZZER_PIN, OUTPUT); 14 | digitalWriteEx(STATUS_BUZZER_PIN, !STATUS_BUZZER_ON_STATE); 15 | #endif 16 | ready = true; 17 | } 18 | 19 | #if STATUS_BUZZER == ON 20 | uint8_t _buzzerHandle = 0; 21 | void buzzerOff() { 22 | digitalWriteEx(STATUS_BUZZER_PIN, !STATUS_BUZZER_ON_STATE); 23 | tasks.setDurationComplete(_buzzerHandle); 24 | _buzzerHandle = 0; 25 | } 26 | #endif 27 | 28 | void Sound::alert() { 29 | if (ready && enabled) { 30 | #if STATUS_BUZZER == ON 31 | digitalWriteEx(STATUS_BUZZER_PIN, STATUS_BUZZER_ON_STATE); 32 | if (_buzzerHandle) tasks.remove(_buzzerHandle); 33 | _buzzerHandle = tasks.add(1000, 0, false, 6, buzzerOff); 34 | #endif 35 | #if STATUS_BUZZER >= 0 36 | tone(STATUS_BUZZER_PIN, STATUS_BUZZER, 1000); 37 | #endif 38 | } 39 | } 40 | 41 | void Sound::beep() { 42 | if (ready && enabled) { 43 | #if STATUS_BUZZER == ON 44 | digitalWriteEx(STATUS_BUZZER_PIN, STATUS_BUZZER_ON_STATE); 45 | if (_buzzerHandle) tasks.remove(_buzzerHandle); 46 | _buzzerHandle = tasks.add(250, 0, false, 6, buzzerOff); 47 | #endif 48 | #if STATUS_BUZZER >= 0 49 | tone(STATUS_BUZZER_PIN, STATUS_BUZZER, 250); 50 | #endif 51 | } 52 | } 53 | 54 | void Sound::click() { 55 | if (ready && enabled) { 56 | #if STATUS_BUZZER == ON 57 | digitalWriteEx(STATUS_BUZZER_PIN, STATUS_BUZZER_ON_STATE); 58 | if (_buzzerHandle) tasks.remove(_buzzerHandle); 59 | _buzzerHandle = tasks.add(50, 0, false, 6, buzzerOff); 60 | #endif 61 | #if STATUS_BUZZER >= 0 62 | tone(STATUS_BUZZER_PIN, STATUS_BUZZER, 50); 63 | #endif 64 | } 65 | } 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /src/lib/sound/Sound.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------------------- 2 | // Sound 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #ifdef STATUS_BUZZER 8 | 9 | class Sound { 10 | public: 11 | void init(); // get sound pins ready 12 | void alert(); // sound/buzzer 13 | void click(); // sound/beep 14 | void beep(); // sound/click 15 | 16 | bool enabled = STATUS_BUZZER_DEFAULT == ON; 17 | private: 18 | bool ready = false; 19 | }; 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /src/lib/tls/PPS.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Pulse Per Second precision timer skew 3 | 4 | #include "PPS.h" 5 | 6 | #if defined(TIME_LOCATION_PPS_SENSE) && (TIME_LOCATION_PPS_SENSE) != OFF 7 | 8 | #include "../tasks/OnTask.h" 9 | 10 | void ppsIsr() { 11 | unsigned long t = micros(); 12 | unsigned long oneSecond = t - pps.lastMicros; 13 | if (oneSecond > 1000000UL - PPS_WINDOW_MICROS && oneSecond < 1000000UL + PPS_WINDOW_MICROS) { 14 | pps.averageSubMicros = (pps.averageSubMicros*(PPS_SECS_TO_AVERAGE - 1) + (oneSecond*16))/PPS_SECS_TO_AVERAGE; 15 | pps.synced = true; 16 | tasks.setPeriodRatioSubMicros((long)pps.averageSubMicros + pps.averageSubMicrosSkew); 17 | } else { 18 | pps.synced = false; 19 | tasks.setPeriodRatioSubMicros(16000000UL); 20 | } 21 | pps.lastMicros = t; 22 | } 23 | 24 | void Pps::init() { 25 | VLF("MSG: PPS, attaching ISR to sense input"); 26 | pinMode(PPS_SENSE_PIN, INPUT_PULLUP); 27 | #if (TIME_LOCATION_PPS_SENSE) == HIGH 28 | attachInterrupt(digitalPinToInterrupt(PPS_SENSE_PIN), ppsIsr, RISING); 29 | #elif (TIME_LOCATION_PPS_SENSE) == LOW 30 | attachInterrupt(digitalPinToInterrupt(PPS_SENSE_PIN), ppsIsr, FALLING); 31 | #elif (TIME_LOCATION_PPS_SENSE) == BOTH 32 | attachInterrupt(digitalPinToInterrupt(PPS_SENSE_PIN), ppsIsr, CHANGE); 33 | #endif 34 | } 35 | 36 | Pps pps; 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /src/lib/tls/PPS.h: -------------------------------------------------------------------------------- 1 | // handle PPS interrupt 2 | #pragma once 3 | 4 | #include "../../Common.h" 5 | 6 | #if defined(TIME_LOCATION_PPS_SENSE) && (TIME_LOCATION_PPS_SENSE) != OFF 7 | 8 | #define PPS_SECS_TO_AVERAGE 40 // running average of 40 samples (1 per second) 9 | #define PPS_WINDOW_MICROS 20000 // +/- window in microseconds to meet synced criteria (2%) 10 | 11 | #if !defined(PPS_SENSE_PIN) || PPS_SENSE_PIN == OFF 12 | #error "Configuration (Config.h): PPS_SENSE_PIN must be defined for TIME_LOCATION_PPS_SENSE ON" 13 | #endif 14 | 15 | class Pps { 16 | public: 17 | // attach interrupt and start PPS 18 | void init(); 19 | 20 | volatile bool synced = false; 21 | 22 | volatile unsigned long averageSubMicros = 16000000UL; 23 | long averageSubMicrosSkew = 0; 24 | volatile unsigned long lastMicros = 0UL; 25 | private: 26 | }; 27 | 28 | extern Pps pps; 29 | 30 | #endif 31 | -------------------------------------------------------------------------------- /src/lib/tls/Tls.h: -------------------------------------------------------------------------------- 1 | 2 | // ----------------------------------------------------------------------------------- 3 | // Time/Location source 4 | #pragma once 5 | 6 | #include "ds3231/DS3231.h" 7 | #include "ds3234/DS3234.h" 8 | #include "gps/GPS.h" 9 | #include "ntp/NTP.h" 10 | #include "sd3031/SD3031.h" 11 | #include "teensy/Teensy.h" 12 | 13 | #include "PPS.h" 14 | -------------------------------------------------------------------------------- /src/lib/tls/TlsBase.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source 3 | -------------------------------------------------------------------------------- /src/lib/tls/TlsBase.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE != OFF 8 | 9 | #include "../calendars/Calendars.h" 10 | 11 | class TimeLocationSource { 12 | public: 13 | // initialize (also enables the RTC PPS if available) 14 | virtual bool init(); 15 | 16 | // restart the device 17 | virtual void restart() {} 18 | 19 | // true if date/time ready 20 | inline bool isReady() { return ready; } 21 | 22 | // set the RTC's time 23 | virtual void set(JulianDate ut1); 24 | virtual void set(int year, int month, int day, int hour, int minute, int second); 25 | 26 | // get the RTC's time, returns true if current 27 | virtual bool get(JulianDate &ut1); 28 | 29 | // get the location 30 | virtual void getSite(double &latitude, double &longitude, float &elevation) { UNUSED(latitude); UNUSED(longitude); UNUSED(elevation); } 31 | 32 | // secondary way to enable PPS 33 | virtual void ppsEnable() {} 34 | 35 | // update from GPS or NTP 36 | virtual void poll() {} 37 | 38 | // not used, date/time is stored as UT1 39 | double DUT1 = 0.0L; 40 | 41 | protected: 42 | bool ready = false; 43 | }; 44 | 45 | #endif 46 | -------------------------------------------------------------------------------- /src/lib/tls/ds3231/DS3231.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source DS3231 RTC support 3 | // uses the default I2C port in most cases; though HAL_WIRE can redirect to another port (as is done for the Teensy3.5/3.6) 4 | #pragma once 5 | 6 | #include "../TlsBase.h" 7 | 8 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == DS3231 || \ 9 | (defined(TIME_LOCATION_SOURCE_FALLBACK) && TIME_LOCATION_SOURCE_FALLBACK == DS3231) 10 | 11 | #ifndef TLS_CLOCK_SKEW 12 | #define TLS_CLOCK_SKEW 0.000139 // in hours, +5 seconds ahead when setting time 13 | #endif 14 | 15 | class TlsDs3231 : public TimeLocationSource { 16 | public: 17 | // initialize (also enables the RTC PPS if available) 18 | bool init(); 19 | 20 | // set the RTC's time 21 | void set(JulianDate ut1); 22 | void set(int year, int month, int day, int hour, int minute, int second); 23 | 24 | // get the RTC's time 25 | bool get(JulianDate &ut1); 26 | 27 | // secondary way to enable PPS 28 | void ppsEnable(); 29 | 30 | // not used, date/time is stored as UT1 31 | double DUT1 = 0.0L; 32 | 33 | private: 34 | }; 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /src/lib/tls/ds3234/DS3234.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source DS3234 RTC support 3 | // uses the default SPI port 4 | #pragma once 5 | 6 | #include "../TlsBase.h" 7 | 8 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == DS3234 || \ 9 | (defined(TIME_LOCATION_SOURCE_FALLBACK) && TIME_LOCATION_SOURCE_FALLBACK == DS3234) 10 | 11 | #if !defined(DS3234_CS_PIN) || DS3234_CS_PIN == OFF 12 | #error "Configuration (Config.h): DS3234_CS_PIN must be defined for TIME_LOCATION_SOURCE DS3234" 13 | #endif 14 | 15 | #ifndef TLS_CLOCK_SKEW 16 | #define TLS_CLOCK_SKEW 0.000139 // in hours, +5 seconds ahead when setting time 17 | #endif 18 | 19 | class TlsDs3234 : public TimeLocationSource { 20 | public: 21 | // initialize (also enables the RTC PPS if available) 22 | bool init(); 23 | 24 | // set the RTC's time 25 | void set(JulianDate ut1); 26 | void set(int year, int month, int day, int hour, int minute, int second); 27 | 28 | // get the RTC's time 29 | bool get(JulianDate &ut1); 30 | 31 | // not used, date/time is stored as UT1 32 | double DUT1 = 0.0L; 33 | 34 | private: 35 | }; 36 | 37 | #endif -------------------------------------------------------------------------------- /src/lib/tls/gps/GPS.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source GPS support 3 | // uses the specified serial port 4 | #pragma once 5 | 6 | #include "../TlsBase.h" 7 | 8 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == GPS 9 | 10 | #ifndef GPS_TIMEOUT_MINUTES 11 | #define GPS_TIMEOUT_MINUTES 10 // wait up to 10 minutes to get lock, use 0 to disable timeout 12 | #endif 13 | #ifndef GPS_MIN_WAIT_MINUTES 14 | #define GPS_MIN_WAIT_MINUTES 2 // minimum wait for stabilization in minutes, use 0 to disable 15 | #endif 16 | 17 | class TlsGPS : public TimeLocationSource { 18 | public: 19 | // initialize (also enables the RTC PPS if available) 20 | // pass a hook to the tls you created so it can be called 21 | bool init(); 22 | 23 | // set the RTC's time 24 | void set(JulianDate ut1); 25 | void set(int year, int month, int day, int hour, int minute, int second); 26 | 27 | // get the RTC's time 28 | bool get(JulianDate &ut1); 29 | 30 | // get the location 31 | void getSite(double &latitude, double &longitude, float &elevation); 32 | 33 | // update from GPS 34 | void poll(); 35 | 36 | // for conversion from UTC to UT1 37 | double DUT1 = 0.0L; 38 | 39 | private: 40 | // validate wait time 41 | bool waitIsValid(); 42 | 43 | // validate time 44 | bool timeIsValid(); 45 | 46 | // validate site 47 | bool siteIsValid(); 48 | 49 | unsigned long startTime = 0; 50 | 51 | bool active = false; 52 | bool activeLink = false; 53 | }; 54 | 55 | #endif 56 | -------------------------------------------------------------------------------- /src/lib/tls/ntp/NTP.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------- 2 | // NTP time code 3 | // from here: https://github.com/PaulStoffregen/Time 4 | #pragma once 5 | 6 | #include "../TlsBase.h" 7 | 8 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == NTP 9 | 10 | #if OPERATIONAL_MODE == WIFI 11 | #include 12 | #elif OPERATIONAL_MODE == ETHERNET_TEENSY41 13 | #include 14 | #else 15 | #include 16 | #endif 17 | 18 | #ifndef NTP_TIMEOUT_SECONDS 19 | #define NTP_TIMEOUT_SECONDS 300 // wait up to 5 minutes to get date/time, use 0 to disable timeout 20 | #endif 21 | 22 | class TlsNTP : public TimeLocationSource { 23 | public: 24 | // initialize (also enables the RTC PPS if available) 25 | bool init(); 26 | 27 | // restart UDP server 28 | void restart(); 29 | 30 | // set the RTC's time 31 | void set(JulianDate ut1); 32 | void set(int year, int month, int day, int hour, int minute, int second); 33 | 34 | // get the RTC's time 35 | bool get(JulianDate &ut1); 36 | 37 | // update from NTP 38 | void poll(); 39 | 40 | // for conversion from UTC to UT1 41 | double DUT1 = 0.0L; 42 | 43 | private: 44 | // send an NTP request to the time server at the given address 45 | void sendNTPpacket(IPAddress &address); 46 | 47 | // NTP time is in the first 48 bytes of message 48 | static const int NTP_PACKET_SIZE = 48; 49 | 50 | // buffer to hold incoming & outgoing packets 51 | uint8_t packetBuffer[NTP_PACKET_SIZE]; 52 | 53 | unsigned long startTime = 0; 54 | 55 | bool active = false; 56 | uint8_t handle = 0; 57 | 58 | }; 59 | 60 | #endif 61 | -------------------------------------------------------------------------------- /src/lib/tls/sd3031/SD3031.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source SD3031 RTC support 3 | // uses the default I2C port in most cases; though HAL_WIRE can redirect to another port (as is done for the Teensy3.5/3.6) 4 | #pragma once 5 | 6 | #include "../TlsBase.h" 7 | 8 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == SD3031 || \ 9 | (defined(TIME_LOCATION_SOURCE_FALLBACK) && TIME_LOCATION_SOURCE_FALLBACK == SD3031) 10 | 11 | #ifndef TLS_CLOCK_SKEW 12 | #define TLS_CLOCK_SKEW 0.0 // in hours 13 | #endif 14 | 15 | class TlsSd3031 : public TimeLocationSource { 16 | public: 17 | // initialize (also enables the RTC PPS if available) 18 | bool init(); 19 | 20 | // set the RTC's time 21 | void set(JulianDate ut1); 22 | void set(int year, int month, int day, int hour, int minute, int second); 23 | 24 | // get the RTC's time 25 | bool get(JulianDate &ut1); 26 | 27 | // not used, date/time is stored as UT1 28 | double DUT1 = 0.0L; 29 | 30 | private: 31 | }; 32 | 33 | #endif 34 | -------------------------------------------------------------------------------- /src/lib/tls/teensy/Teensy.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source TEENSY 3.2 RTC support 3 | 4 | #include "Teensy.h" 5 | 6 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == TEENSY || \ 7 | (defined(TIME_LOCATION_SOURCE_FALLBACK) && TIME_LOCATION_SOURCE_FALLBACK == TEENSY) 8 | 9 | #include // https://github.com/PaulStoffregen/Time/archive/master.zip 10 | 11 | bool TlsTeensy::init() { 12 | ready = true; 13 | return ready; 14 | } 15 | 16 | void TlsTeensy::set(JulianDate ut1) { 17 | GregorianDate greg = calendars.julianDayToGregorian(ut1); 18 | 19 | double f1 = fabs(ut1.hour) + TLS_CLOCK_SKEW; 20 | int h = floor(f1); 21 | double m = (f1 - h)*60.0; 22 | double s = (m - floor(m))*60.0; 23 | 24 | set(greg.year, greg.month, greg.day, h, floor(m), floor(s)); 25 | } 26 | 27 | void TlsTeensy::set(int year, int month, int day, int hour, int minute, int second) { 28 | setTime(hour, minute, second, day, month, year); 29 | unsigned long TeensyTime = now(); // get time in epoch 30 | Teensy3Clock.set(TeensyTime); // set Teensy time 31 | } 32 | 33 | bool TlsTeensy::get(JulianDate &ut1) { 34 | if (!ready) return false; 35 | 36 | unsigned long TeensyTime = Teensy3Clock.get(); // get time from Teensy RTC 37 | setTime(TeensyTime); // set system time 38 | 39 | if (year() >= 0 && year() <= 3000 && month() >= 1 && month() <= 12 && day() >= 1 && day() <= 31 && 40 | hour() <= 23 && minute() <= 59 && second() <= 59) { 41 | GregorianDate greg; greg.year = year(); greg.month = month(); greg.day = day(); 42 | ut1 = calendars.gregorianToJulianDay(greg); 43 | ut1.hour = hour() + minute()/60.0 + second()/3600.0; 44 | } 45 | 46 | return true; 47 | } 48 | 49 | #endif -------------------------------------------------------------------------------- /src/lib/tls/teensy/Teensy.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Time/Location source TEENSY 3.2 RTC support 3 | #pragma once 4 | 5 | #include "../TlsBase.h" 6 | 7 | #if defined(TIME_LOCATION_SOURCE) && TIME_LOCATION_SOURCE == TEENSY || \ 8 | (defined(TIME_LOCATION_SOURCE_FALLBACK) && TIME_LOCATION_SOURCE_FALLBACK == TEENSY) 9 | 10 | #ifndef TLS_CLOCK_SKEW 11 | #define TLS_CLOCK_SKEW 0.000139 // in hours, +5 seconds ahead when setting time 12 | #endif 13 | 14 | class TlsTeensy : public TimeLocationSource { 15 | public: 16 | // initialize (also enables the RTC PPS if available) 17 | bool init(); 18 | 19 | // set the RTC's time 20 | void set(JulianDate ut1); 21 | void set(int year, int month, int day, int hour, int minute, int second); 22 | 23 | // get the RTC's time 24 | bool get(JulianDate &ut1); 25 | 26 | // not used, date/time is stored as UT1 27 | double DUT1 = 0.0L; 28 | 29 | private: 30 | }; 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /src/lib/watchdog/Watchdog.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------------------- 2 | // General purpose "virtual" watchdog 3 | #include "Watchdog.h" 4 | 5 | #if defined(WATCHDOG) && WATCHDOG != OFF || true 6 | 7 | #ifndef __AVR_ATmega2560__ 8 | #include "../tasks/OnTask.h" 9 | void watchdogWrapper() { watchdog.poll(); } 10 | #else 11 | void (*mega2560restart) (void) = 0; 12 | #include 13 | #endif 14 | 15 | void Watchdog::enable(int seconds) { 16 | #ifndef __AVR_ATmega2560__ 17 | if (this->seconds == -1) { 18 | this->seconds = seconds; 19 | 20 | VF("MSG: Watchdog, start monitor task (100ms rate priority 0)... "); 21 | uint8_t taskHandle = tasks.add(100, 0, true, 0, watchdogWrapper, "wdog"); 22 | 23 | if (taskHandle) { 24 | VLF("success"); 25 | if (!tasks.requestHardwareTimer(taskHandle, 0)) { DLF("WRN: Watchdog::enable(), didn't get h/w timer (using s/w timer!!!)"); } 26 | } else { 27 | VLF("FAILED!"); 28 | return; 29 | } 30 | } 31 | #else 32 | if (seconds == 1) wdt_enable(WDTO_1S); else 33 | if (seconds == 2) wdt_enable(WDTO_2S); else 34 | if (seconds == 4) wdt_enable(WDTO_4S); else 35 | if (seconds == 8) wdt_enable(WDTO_8S); else return; 36 | #endif 37 | enabled = true; 38 | } 39 | 40 | void Watchdog::disable() { 41 | #ifndef __AVR_ATmega2560__ 42 | enabled = false; 43 | #else 44 | wdt_disable(); 45 | #endif 46 | } 47 | 48 | void Watchdog::reset() { 49 | #ifndef __AVR_ATmega2560__ 50 | count = 0; 51 | #else 52 | wdt_reset(); 53 | #endif 54 | } 55 | 56 | void Watchdog::poll() { 57 | if (!enabled) return; 58 | if (count++ > 10 * seconds) { HAL_RESET(); } 59 | } 60 | 61 | Watchdog watchdog; 62 | 63 | #endif 64 | -------------------------------------------------------------------------------- /src/lib/watchdog/Watchdog.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------------------------------------------------- 2 | // General purpose "virtual" watchdog 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | #if defined(WATCHDOG) && WATCHDOG != OFF || true 8 | 9 | class Watchdog { 10 | public: 11 | // initialize and start the watchdog with timeout (to reset MCU) of seconds 12 | void enable(int seconds); 13 | 14 | // call at least once per timeout period or the MCU will be reset if the WD is enabled 15 | void reset(); 16 | 17 | // disable the watchdog 18 | void disable(); 19 | 20 | // for internal use 21 | void poll(); 22 | 23 | private: 24 | volatile int16_t count = 0; 25 | volatile int16_t seconds = -1; 26 | volatile bool enabled = false; 27 | }; 28 | 29 | extern Watchdog watchdog; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/lib/wifi/cmdServer/CmdServer.h: -------------------------------------------------------------------------------- 1 | // wifi IP command server 2 | #pragma once 3 | 4 | #include "../../../Common.h" 5 | #include "../WifiManager.h" 6 | 7 | #if OPERATIONAL_MODE == WIFI && COMMAND_SERVER != OFF 8 | 9 | class CmdServer { 10 | public: 11 | CmdServer(uint32_t port, long clientTimeoutMs, bool persist = false); 12 | void begin(); 13 | void handleClient(); 14 | 15 | private: 16 | WiFiServer *cmdSvr; 17 | WiFiClient cmdSvrClient; 18 | 19 | unsigned long clientTimeoutMs; 20 | unsigned long clientEndTimeMs = 0; 21 | bool persist; 22 | long port; 23 | }; 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /src/lib/wifi/webServer/WebServer.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Web server 3 | 4 | #include "WebServer.h" 5 | 6 | #if OPERATIONAL_MODE == WIFI && WEB_SERVER == ON 7 | 8 | #if defined(ESP32) 9 | WebServer www(80); 10 | #elif defined(ESP8266) 11 | ESP8266WebServer www(80); 12 | #endif 13 | 14 | #endif 15 | -------------------------------------------------------------------------------- /src/lib/wifi/webServer/WebServer.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Web server 3 | #pragma once 4 | 5 | #include "../../../Common.h" 6 | #include "../WifiManager.h" 7 | 8 | #if OPERATIONAL_MODE == WIFI && WEB_SERVER == ON 9 | 10 | #if defined(ESP32) 11 | #include 12 | #elif defined(ESP8266) 13 | #include 14 | #else 15 | #error "Configuration (Config.h): No Wifi support is present for this device" 16 | #endif 17 | 18 | #if defined(ESP32) 19 | extern WebServer www; 20 | #define sendContentAndClear(x) sendContent(x); x = ""; 21 | #elif defined(ESP8266) 22 | extern ESP8266WebServer www; 23 | #define sendContentAndClear(x) sendContent(x); x = ""; delay(1); 24 | #endif 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /src/libApp/bleGamepad/BleConfig.h: -------------------------------------------------------------------------------- 1 | // bleGamepad configuration file 2 | #pragma once 3 | 4 | //*********************************************************************************************************** 5 | // Configuration settings 6 | //*********************************************************************************************************** 7 | 8 | // ON/OFF unless noted otherwise 9 | 10 | // Direction button swaps 11 | #define NS_SWAP OFF // ON reverses direction buttons from OnStep standard 12 | #define EW_SWAP OFF // East/West swap 13 | 14 | #define LED_ENABLE ON // LED on/off behavior, OFF disables LED BLE connected/disconnected 15 | // indication. ON = LED off when connected, on when disconnected 16 | // REV = LED on when connected, off when disconnected 17 | 18 | #define FOCUS_INIT ON // Focuser moves to half-position on M button "Start tracking" press, 19 | // moves to "0" position on "M" button "Park". OFF disables feature 20 | 21 | #define SOUND ON // ON, Enables beeps and alerts 22 | 23 | #define M_BUTTON ON // ON, Add addtional functions to M button. 24 | // For supported GamePads only. 25 | 26 | #define INIT_ALIGN ON // ON, Enables M button align from "At Home" (startup) with 3 27 | // star alignment (see ALIGNSTARS to change number of stars) 28 | 29 | #define MODE_D OFF // OFF, uses Mode B, ON use Mode D for GamePad if it supports it. 30 | // V2.0 code for backward compatabilty. 31 | 32 | #define M_SINGLE_CLICK OFF // OFF, ON, M button will activate on a single click as in 33 | // V2.0 code, for backward compatabilty. 34 | 35 | //*********************************************************************************************************** 36 | -------------------------------------------------------------------------------- /src/libApp/bleGamepad/BleGamepad.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Bluetooth Gamepad variables 3 | 4 | #pragma once 5 | 6 | #include "../../Common.h" 7 | 8 | #if defined(BLE_GAMEPAD) && BLE_GAMEPAD == ON 9 | extern void bleInit(); 10 | extern void bleSetup(); 11 | extern void bleTimers(); 12 | extern void bleConnTest(); 13 | #endif 14 | -------------------------------------------------------------------------------- /src/libApp/misc/Misc.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Misc functions to help with commands, etc. 3 | #pragma once 4 | 5 | #include "../../Common.h" 6 | 7 | enum DriverType {DT_NONE, DT_SERVO, DT_STEP_DIR_STANDARD, DT_STEP_DIR_TMC_SPI, DT_STEP_DIR_LEGACY}; 8 | 9 | typedef struct AxisSettings { 10 | double stepsPerMeasure; 11 | int8_t reverse; 12 | int16_t min; 13 | int16_t max; 14 | int16_t microsteps; 15 | int16_t microstepsGoto; 16 | int16_t currentHold; 17 | int16_t currentRun; 18 | int16_t currentGoto; 19 | float p, i, d, pGoto, iGoto, dGoto; 20 | double param1; 21 | double param2; 22 | double param3; 23 | double param4; 24 | double param5; 25 | double param6; 26 | DriverType driverType; 27 | } AxisSettings; 28 | 29 | // remove leading and trailing 0's 30 | void stripNum(char* s); 31 | 32 | // convert hex to int, returns -1 on error 33 | int hexToInt(String s); 34 | 35 | // convert time to compact byte representation for intervalometer 36 | uint8_t timeToByte(float t); 37 | 38 | // convert compact byte representation to time for intervalometer 39 | float byteToTime(uint8_t b); 40 | 41 | // convert axis settings string into numeric form 42 | bool decodeAxisSettings(char* s, AxisSettings* a); 43 | 44 | // convert axis settings string into numeric form 45 | bool decodeAxisSettingsX(char* s, AxisSettings* a); 46 | 47 | // validate axis settings for a given axis and mount type 48 | bool validateAxisSettings(int axisNum, bool altAz, AxisSettings a); 49 | 50 | // validate axis settings for a given axis and mount type 51 | bool validateAxisSettingsX(int axisNum, AxisSettings a); 52 | 53 | // return temperature string with proper value and units for this locale 54 | void localeTemperature(char* temperatureStr); 55 | 56 | // return pressure string with proper value and units for this locale 57 | void localePressure(char* pressureStr); 58 | 59 | // return humidity string with proper value and units for this locale 60 | void localeHumidity(char* humidityStr); 61 | -------------------------------------------------------------------------------- /src/libApp/status/StateAuxiliary.cpp: -------------------------------------------------------------------------------- 1 | // update controller state 2 | #include "State.h" 3 | 4 | #include "Status.h" 5 | #include "../../lib/tasks/OnTask.h" 6 | #include "../../libApp/cmd/Cmd.h" 7 | 8 | bool State::updateAuxiliary(bool all, bool now) { 9 | if (!now && millis() - lastAuxPageLoadTime > 2000) return true; 10 | 11 | bool valid; 12 | 13 | // get feature status 14 | for (uint8_t i = 0; i < 8; i++) { 15 | char *value1_str = NULL; 16 | char *value2_str = NULL; 17 | char *value3_str = NULL; 18 | char *value4_str = NULL; 19 | char cmd[40], out[40]; 20 | 21 | if (all || (status.feature[i].purpose == SWITCH || status.feature[i].purpose == ANALOG_OUTPUT || status.feature[i].purpose == DEW_HEATER || status.feature[i].purpose == INTERVALOMETER)) { 22 | sprintf(cmd,":GXX%d#", i + 1); 23 | if (!onStep.command(cmd, out) || strlen(out) == 0) valid = false; else valid = true; Y; 24 | if (!valid) { 25 | status.feature[i].value1 = 0; 26 | status.feature[i].value2 = NAN; 27 | status.feature[i].value3 = NAN; 28 | status.feature[i].value4 = NAN; 29 | return false; 30 | } 31 | 32 | value2_str = strstr(out,","); 33 | if (value2_str) { 34 | value2_str[0] = 0; 35 | value2_str++; 36 | value3_str = strstr(value2_str, ","); 37 | if (value3_str) { 38 | value3_str[0] = 0; 39 | value3_str++; 40 | value4_str = strstr(value3_str, ","); 41 | if (value4_str) { 42 | value4_str[0] = 0; 43 | value4_str++; 44 | } 45 | } 46 | } 47 | value1_str = out; 48 | if (!value1_str) valid = false; 49 | 50 | if (valid) { 51 | if (value1_str) status.feature[i].value1 = atoi(value1_str); 52 | if (value2_str) status.feature[i].value2 = atof(value2_str); 53 | if (value3_str) status.feature[i].value3 = atof(value3_str); 54 | if (value4_str) status.feature[i].value4 = atof(value4_str); 55 | } 56 | } 57 | } 58 | return true; 59 | } 60 | -------------------------------------------------------------------------------- /src/libApp/status/StateRotator.cpp: -------------------------------------------------------------------------------- 1 | // update rotator state 2 | #include "State.h" 3 | 4 | #include "Status.h" 5 | #include "../../lib/tasks/OnTask.h" 6 | #include "../../libApp/cmd/Cmd.h" 7 | #include "../../locales/Locale.h" 8 | #include "../../lib/convert/Convert.h" 9 | 10 | void State::updateRotator(bool now) 11 | { 12 | if (!now && millis() - lastRotatorPageLoadTime > 2000) return; 13 | 14 | char temp[80], temp1[80]; 15 | 16 | if (status.rotatorFound == SD_TRUE) { 17 | 18 | // rotator position 19 | if (onStep.command(":rG#", temp1)) 20 | { 21 | temp1[4] = 0; 22 | strcpy(temp, temp1); 23 | strcat(temp, "°"); 24 | strcat(temp, &temp1[5]); 25 | strcat(temp, "'"); 26 | } else strcpy(temp, "?"); 27 | strncpyex(rotatorPositionStr, temp, 20); Y; 28 | 29 | // rotator working slew rate 30 | if (status.getVersionMajor() >= 10) 31 | { 32 | if (onStep.command(":rW#", temp)) 33 | { 34 | double s = atof(temp); 35 | if (s != 0.0) { 36 | sprintF(rotateSlewSpeedStr, "%0.1f°/s", s); 37 | } else strcpy(rotateSlewSpeedStr, "?"); 38 | } else strcpy(rotateSlewSpeedStr, "?"); 39 | } else strcpy(rotateSlewSpeedStr, "?"); 40 | 41 | // rotator status 42 | if (onStep.command(":rT#", temp)) 43 | { 44 | rotatorSlewing = (bool)strchr(temp, 'M'); 45 | rotatorDerotate = (bool)strchr(temp, 'D'); 46 | rotatorDerotateReverse = (bool)strchr(temp, 'R'); 47 | switch (temp[strlen(temp) - 1] - '0') { 48 | case 1: rotatorGotoRate = 1; break; 49 | case 2: rotatorGotoRate = 2; break; 50 | case 3: rotatorGotoRate = 3; break; 51 | case 4: rotatorGotoRate = 4; break; 52 | case 5: rotatorGotoRate = 5; break; 53 | default: rotatorGotoRate = 0; break; 54 | } 55 | } else { 56 | rotatorSlewing = false; 57 | rotatorDerotate = false; 58 | rotatorDerotateReverse = false; 59 | rotatorGotoRate = 0; 60 | } 61 | Y; 62 | } 63 | } -------------------------------------------------------------------------------- /src/libApp/status/Version.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Version information for SWS 3 | #include "Version.h" 4 | 5 | Version firmwareVersion; 6 | -------------------------------------------------------------------------------- /src/libApp/status/Version.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Version information for SWS 3 | #pragma once 4 | 5 | class Version { 6 | public: 7 | char str[30]; 8 | }; 9 | 10 | extern Version firmwareVersion; 11 | -------------------------------------------------------------------------------- /src/locales/Locale.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Locale 3 | #pragma once 4 | 5 | #include "../Constants.h" 6 | #include "../../Config.h" 7 | 8 | #include "Locales.h" 9 | 10 | // see Strings_xx.h for individual locale translations 11 | 12 | // ISO639-1 language codes (these control the inclusion of individual Strings_xx.h files as specified in Config.h) 13 | #if DISPLAY_LANGUAGE == L_cn 14 | #include "Strings_cn.h" 15 | #define UNITS METRIC 16 | #endif 17 | #if DISPLAY_LANGUAGE == L_de 18 | #include "Strings_de.h" 19 | #define UNITS METRIC 20 | #endif 21 | #if DISPLAY_LANGUAGE == L_en 22 | #include "Strings_en.h" 23 | #define UNITS METRIC 24 | #endif 25 | #if DISPLAY_LANGUAGE == L_us // not ISO639-1 but might be useful 26 | #include "Strings_en.h" 27 | #define UNITS IMPERIAL 28 | #endif 29 | #if DISPLAY_LANGUAGE == L_es 30 | #include "Strings_es.h" 31 | #define UNITS METRIC 32 | #endif 33 | 34 | // misc. locale support functions 35 | #ifndef DISPLAY_UNITS 36 | #define DISPLAY_UNITS UNITS 37 | #else 38 | #if DISPLAY_UNITS == LOCALE_DEFAULT 39 | #undef DISPLAY_UNITS 40 | #define DISPLAY_UNITS UNITS 41 | #endif 42 | #endif 43 | 44 | #if DISPLAY_UNITS == IMPERIAL 45 | #define nativeToCelsius(t) ((t - 32.0F)*(5.0F/9.0F)) 46 | #define celsiusToNative(t) (t*(9.0F/5.0F) + 32.0F) 47 | #define nativeToCelsiusRelative(t) (t*(5.0F/9.0F)) 48 | #define celsiusToNativeRelative(t) (t*(9.0F/5.0F)) 49 | #define TEMPERATURE_UNITS_ABV "F" 50 | #else 51 | #define nativeToCelsius(t) (t) 52 | #define celsiusToNative(t) (t) 53 | #define nativeToCelsiusRelative(t) (t) 54 | #define celsiusToNativeRelative(t) (t) 55 | #define TEMPERATURE_UNITS_ABV "C" 56 | #endif 57 | -------------------------------------------------------------------------------- /src/locales/Locales.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Locales 3 | #pragma once 4 | 5 | // see Strings_xx.h for individual locale translations 6 | 7 | // languages (one unique numeric code required for each) 8 | #define L_cn 1 9 | #define L_de 2 10 | #define L_en 3 11 | #define L_us 4 12 | #define L_es 5 13 | #define L_fr 6 14 | -------------------------------------------------------------------------------- /src/pages/Err404.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Error not found, 404 3 | 4 | #include "Pages.common.h" 5 | 6 | void handleNotFound() { 7 | String message = ""; 8 | 9 | message.concat("SmartWebServer, 404 File Not Found

\n"); 10 | message.concat("URI: " + www.uri() + "
\n"); 11 | 12 | message.concat("Method: "); 13 | if (www.method() == HTTP_GET) message.concat("GET
\n"); else 14 | if (www.method() == HTTP_PUT) message.concat("PUT
\n"); else 15 | if (www.method() == HTTP_POST) message.concat("POST
\n"); else message.concat("Unknown
\n"); 16 | 17 | message.concat("\nArguments: " + String(www.args()) + "
\n"); 18 | for (uint8_t i = 0; i < www.args(); i++){ 19 | message.concat(" " + www.argName(i) + ": " + www.arg(i) + "
\n"); 20 | } 21 | 22 | message.concat(""); 23 | 24 | www.send(404, "text/html", message); 25 | } 26 | -------------------------------------------------------------------------------- /src/pages/KeyValue.cpp: -------------------------------------------------------------------------------- 1 | // key/value handling 2 | #include 3 | #include "KeyValue.h" 4 | 5 | String keyValueString(String key, String value1, String value2, String value3, String value4) { 6 | return key + "|" + value1 + value2 + value3 + value4 + "\n"; 7 | } 8 | 9 | String keyValueToggleBoolSelected(String keyOn, String keyOff, bool selectState) { 10 | return keyOn + "|" + (selectState ? "selected\n" : "unselected\n") + keyOff + "|" + (selectState ? "unselected\n" : "selected\n"); 11 | } 12 | 13 | String keyValueBoolSelected(String key, bool selectState) { 14 | return key + "|" + (selectState ? "selected\n" : "unselected\n"); 15 | } 16 | 17 | String keyValueBoolEnabled(String key, bool state) { 18 | return key + "|" + (state ? "enabled\n" : "disabled\n"); 19 | } 20 | -------------------------------------------------------------------------------- /src/pages/KeyValue.h: -------------------------------------------------------------------------------- 1 | // key/value handling 2 | #pragma once 3 | 4 | String keyValueString(String key, String value1, String value2 = "", String value3 = "", String value4 = ""); 5 | String keyValueToggleBoolSelected(String keyOn, String keyOff, bool selectState); 6 | String keyValueBoolSelected(String key, bool selectState); 7 | String keyValueBoolEnabled(String key, bool state); 8 | -------------------------------------------------------------------------------- /src/pages/LibraryHelp.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Libraryhelp 3 | #include "LibraryHelp.h" 4 | 5 | #include "Pages.common.h" 6 | 7 | void handleLibraryHelp() { 8 | String data = ""; 9 | 10 | www.setContentLength(CONTENT_LENGTH_UNKNOWN); 11 | www.sendHeader("Cache-Control", "no-cache"); 12 | www.send(200, "text/html", String()); 13 | 14 | data.concat(F("Library Help")); 15 | data.concat(FPSTR(html_libCatalogHelp1)); 16 | data.concat(FPSTR(html_libCatalogHelp2)); 17 | data.concat(F("")); 18 | 19 | www.sendContentAndClear(data); 20 | www.sendContent(""); 21 | } 22 | -------------------------------------------------------------------------------- /src/pages/LibraryHelp.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Library help 3 | #pragma once 4 | 5 | #include "htmlHeaders.h" 6 | #include "htmlMessages.h" 7 | #include "htmlScripts.h" 8 | 9 | const char html_libCatalogHelp1[] PROGMEM = 10 | "Data format:
"
11 | "Object Name Cat    RA       Dec   
" 12 | "ccccccccccc,ccc,HH:MM:SS,sDD*MM:SS
" 13 | "Sample data:
"
14 | "$PlaNeb1
" 15 | "M97 ,PN ,11:15:53,+54*55:24
" 16 | "M27 ,PN ,20:00:26,+22*46:29
" 17 | "
" 18 | L_CAT_EXAMPLE1 L_CAT_EXAMPLE2 L_CAT_EXAMPLE3 L_CAT_EXAMPLE4 L_CAT_EXAMPLE5 19 | " UNK = Unknown
" 20 | " OC = Open Cluster
" 21 | " GC = Globular Cluster
"; 22 | const char html_libCatalogHelp2[] PROGMEM = 23 | " PN = Planetary Nebula
" 24 | " DN = Dark Nebula
" 25 | " SG = Spiral Galaxy
" 26 | " EG = Elliptical Galaxy
" 27 | " IG = Irregular Galaxy
" 28 | " KNT = Knot
" 29 | " SNR = Supernova Remnant
" 30 | " GAL = Galaxy
" 31 | " CN = Cluster w/Nebula
" 32 | " STR = Star
" 33 | " PLA = Planet
" 34 | " CMT = Comet
" 35 | " AST = Asteroid

" 36 | L_CAT_EXAMPLE6 L_CAT_EXAMPLE7 37 | "
\n"; 38 | -------------------------------------------------------------------------------- /src/pages/Page.h: -------------------------------------------------------------------------------- 1 | // SWS standard page 2 | #pragma once 3 | 4 | #include "htmlHeaders.h" 5 | #include "htmlMessages.h" 6 | #include "htmlScripts.h" 7 | 8 | #define PAGE_CONTROLLER 0 9 | #define PAGE_MOUNT 1 10 | #define PAGE_ROTATOR 2 11 | #define PAGE_FOCUSER 3 12 | #define PAGE_AUXILIARY 4 13 | #define PAGE_ENCODERS 5 14 | #define PAGE_NETWORK 6 15 | 16 | void pageHeader(int selected); 17 | 18 | const char html_onstep_header_begin[] PROGMEM = "
"; 19 | const char html_onstep_header_title[] PROGMEM = "Smart Web Server "; 20 | const char html_onstep_header_links[] PROGMEM = ")
"; 21 | const char html_onstep_header_end[] PROGMEM = "
\n"; 22 | const char html_onstep_page_begin[] PROGMEM = "
\n"; 23 | 24 | const char html_links_idx_begin[] PROGMEM = ""; 26 | 27 | const char html_links_mnt_begin[] PROGMEM = ""; 29 | 30 | const char html_links_rot_begin[] PROGMEM = ""; 32 | 33 | const char html_links_foc_begin[] PROGMEM = ""; 35 | 36 | const char html_links_aux_begin[] PROGMEM = ""; 38 | 39 | const char html_links_enc_begin[] PROGMEM = ""; 41 | 42 | const char html_links_net_begin[] PROGMEM = ""; 44 | 45 | const char html_links_selected[] PROGMEM =" style='background-color: " COLOR_LINK_SELECTED_BACKGROUND ";' "; 46 | -------------------------------------------------------------------------------- /src/pages/Pages.common.h: -------------------------------------------------------------------------------- 1 | 2 | #include "../Common.h" 3 | #include "../locales/Locale.h" 4 | #include "../libApp/misc/Misc.h" 5 | #include "../libApp/cmd/Cmd.h" 6 | #include "../libApp/status/Status.h" 7 | #include "../libApp/encoders/Encoders.h" 8 | #include "../lib/ethernet/webServer/WebServer.h" 9 | #include "../lib/wifi/webServer/WebServer.h" 10 | #include "../lib/convert/Convert.h" 11 | -------------------------------------------------------------------------------- /src/pages/Pages.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Display and process data from webpages 3 | 4 | #include 5 | #include "../Constants.h" 6 | #include "../../Config.h" 7 | #include "../../Extended.config.h" 8 | 9 | void handleRoot(); 10 | void indexAjaxGet(); 11 | void indexAjax(); 12 | 13 | void handleMount(); 14 | void mountAjaxGet(); 15 | void mountAjax(); 16 | void handleLibraryHelp(); 17 | 18 | void handleRotator(); 19 | void rotatorAjaxGet(); 20 | void rotatorAjax(); 21 | 22 | void handleFocuser(); 23 | void focuserAjaxGet(); 24 | void focuserAjax(); 25 | 26 | void handleAux(); 27 | void auxAjaxGet(); 28 | void auxAjax(); 29 | 30 | #if ENCODERS == ON 31 | void handleEncoders(); 32 | void encAjaxGet(); 33 | void encAjax(); 34 | #endif 35 | 36 | void handleNetwork(); 37 | 38 | void handleNotFound(); 39 | -------------------------------------------------------------------------------- /src/pages/auxiliary/Auxiliary.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Telescope auxiliary feature related functions 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | const char html_auxOnSwitch[] PROGMEM = 10 | ""; 11 | const char html_auxOffSwitch[] PROGMEM = 12 | "\n"; 13 | 14 | const char html_auxStartStop1[] PROGMEM = "\n"; 17 | 18 | const char html_auxAnalog[] PROGMEM ="%s
"; 15 | 16 | const char html_mountAngle[] PROGMEM = 17 | "OnStep: %s%s)

"; 18 | 19 | const char html_indexDriverStatus[] PROGMEM = 20 | L_DRIVER " " L_STATUS ": %s
"; 21 | 22 | const char html_encAxisValueTpd[] PROGMEM = 23 | L_ENC_SET_TPD ": %s
\n"; 24 | 25 | const char html_encAxisValueReverse[] PROGMEM = 26 | L_ADV_SET_REV ": %s
\n"; 27 | 28 | const char html_encAxisValueSyncThreshold[] PROGMEM = 29 | L_ENC_SYNC_THLD ": %ld arc-sec
\n"; 30 | 31 | const char html_encFormBegin[] PROGMEM = 32 | "
\n"; 33 | 34 | const char html_encFormEnd[] PROGMEM = 35 | "

\n"; 36 | 37 | const char html_encAxisTpd[] PROGMEM = 38 | L_ENC_SET_TPD ":
" 39 | "
\n"; 40 | 41 | const char html_encAxisReverse[] PROGMEM = 42 | L_ADV_SET_REV ", " L_ADV_BOOL ":
" 43 | "
\n"; 44 | 45 | const char html_encAxisSyncThreshold[] PROGMEM = 46 | L_ENC_SYNC_THLD ", " L_ENC_SYNC_THLD_UNITS ":
" 47 | "
\n"; 48 | 49 | const char html_encUpload[] PROGMEM = 50 | "\n"; 51 | 52 | const char html_encAxisRevert[] PROGMEM = 53 | "\n"; 54 | -------------------------------------------------------------------------------- /src/pages/encoders/Encoders.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Encoders 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #if ENCODERS == ON 10 | #include "SyncTile.h" 11 | #include "AxisTile.h" 12 | #endif 13 | -------------------------------------------------------------------------------- /src/pages/encoders/SyncTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Encoder Sync tile 3 | #include "SyncTile.h" 4 | 5 | #include "../../lib/nv/Nv.h" 6 | 7 | #include "../KeyValue.h" 8 | #include "../Pages.common.h" 9 | 10 | #if ENCODERS == ON 11 | 12 | // create the related webpage tile 13 | void syncTile(String &data) 14 | { 15 | char temp[240] = ""; 16 | 17 | sprintf_P(temp, html_tile_beg, "22em", "15em", "Sync Control"); 18 | data.concat(temp); 19 | data.concat(F("

")); 20 | 21 | sprintf_P(temp, html_form_begin, "enc.htm"); 22 | data.concat(temp); 23 | 24 | data.concat(FPSTR(html_syncOnStepNow)); 25 | data.concat(FPSTR(html_syncEncodersNow)); 26 | 27 | data.concat(FPSTR(html_syncAuto)); 28 | www.sendContentAndClear(data); 29 | 30 | data.concat(F("
")); 31 | 32 | #ifdef ENC_ABSOLUTE 33 | data.concat(FPSTR(html_zeroEncodersNow)); 34 | www.sendContentAndClear(data); 35 | #endif 36 | 37 | data.concat(F("
")); 38 | 39 | data.concat(FPSTR(html_form_end)); 40 | 41 | data.concat(FPSTR(html_tile_end)); 42 | www.sendContentAndClear(data); 43 | } 44 | 45 | // use Ajax key/value pairs to pass related data to the web client in the background 46 | void syncTileAjax(String &data) 47 | { 48 | data.concat(keyValueToggleBoolSelected("enc_as_on", "enc_as_off", encoders.settings.autoSync)); 49 | www.sendContentAndClear(data); 50 | } 51 | 52 | // pass related data back to OnStep 53 | extern void syncTileGet() 54 | { 55 | String v; 56 | 57 | v = www.arg("enc"); 58 | if (!v.equals(EmptyStr)) 59 | { 60 | if (v.equals("o2e")) encoders.syncFromOnStep(); 61 | if (v.equals("e2o")) encoders.syncToOnStep(); 62 | #ifdef ENC_ABSOLUTE 63 | if (v.equals("zro")) encoders.originFromOnStep(); 64 | #endif 65 | if (v.equals("on")) encoders.settings.autoSync = true; 66 | if (v.equals("off")) encoders.settings.autoSync = false; 67 | nv.updateBytes(NV_ENCODER_SETTINGS_BASE, &encoders.settings, sizeof(EncoderSettings)); 68 | } 69 | } 70 | 71 | #endif 72 | -------------------------------------------------------------------------------- /src/pages/encoders/SyncTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Encoder Sync tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void syncTile(String &data); 10 | extern void syncTileAjax(String &data); 11 | extern void syncTileGet(); 12 | 13 | const char html_syncOnStepNow[] PROGMEM = 14 | "" 15 | "
\n"; 16 | 17 | #ifdef ENC_ABSOLUTE 18 | const char html_zeroEncodersNow[] PROGMEM = 19 | "" 20 | "
\n"; 21 | #endif 22 | 23 | const char html_syncEncodersNow[] PROGMEM = 24 | "" 25 | "
\n"; 26 | 27 | const char html_syncAuto[] PROGMEM = "
" 28 | L_ENC_AUTO_SYNC ":
" 29 | "" 30 | "" 31 | "
\n"; 32 | -------------------------------------------------------------------------------- /src/pages/focuser/BacklashTcfTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Focuser Backlash tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void focuserBacklashTcfTile(String &data); 10 | extern void focuserBacklashTcfTileAjax(String &data); 11 | extern void focuserBacklashTcfTileGet(); 12 | 13 | const char html_backlashValue[] PROGMEM = 14 | L_BACKLASH ": %s step(s)
"; 15 | 16 | const char html_tcfDeadbandValue[] PROGMEM = 17 | L_DEADBAND ": %s step(s)
"; 18 | 19 | const char html_tcfEnableValue[] PROGMEM = 20 | L_TCF_COEF_EN ": %s
"; 21 | 22 | const char html_tcfCoefValue[] PROGMEM = 23 | L_TCF_COEF ": %s
"; 24 | 25 | const char html_backlash[] PROGMEM = 26 | " " L_BACKLASH_RANGE_AXIS3UP "
"; 27 | 28 | const char html_tcfDeadband[] PROGMEM = 29 | " " L_DEADBAND_RANGE_AXIS4UP "
"; 30 | 31 | const char html_tcfEnable[] PROGMEM = 32 | " " L_TCF_COEF_EN_AXIS4UP "
"; 33 | 34 | const char html_tcfCoef[] PROGMEM = 35 | " " L_TCF_COEF_RANGE_AXIS4UP "
"; 36 | -------------------------------------------------------------------------------- /src/pages/focuser/Focuser.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Settings 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #include "SelectTile.h" 10 | #include "HomeTile.h" 11 | #include "SlewingTile.h" 12 | #include "BacklashTcfTile.h" 13 | -------------------------------------------------------------------------------- /src/pages/focuser/HomeTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Focuser Home tile 3 | #include "HomeTile.h" 4 | 5 | #include "../KeyValue.h" 6 | #include "../Pages.common.h" 7 | 8 | // create the related webpage tile 9 | void focuserHomeTile(String &data) 10 | { 11 | char temp[240] = ""; 12 | 13 | sprintf_P(temp, html_tile_beg, "22em", "13em", L_HOMING); 14 | data.concat(temp); 15 | data.concat(F("

")); 16 | 17 | data.concat(FPSTR(html_focuserHome)); 18 | 19 | data.concat(F("
")); 20 | 21 | data.concat(FPSTR(html_tile_end)); 22 | www.sendContentAndClear(data); 23 | } 24 | 25 | // use Ajax key/value pairs to pass related data to the web client in the background 26 | void focuserHomeTileAjax(String &data) 27 | { 28 | UNUSED(data); 29 | } 30 | 31 | // pass related data back to OnStep 32 | extern void focuserHomeTileGet() 33 | { 34 | String v; 35 | v = www.arg("dr"); 36 | if (!v.equals(EmptyStr)) 37 | { 38 | if (v.equals("FH")) onStep.commandBlind(":FH#"); // reset focuser at home (half travel) 39 | if (v.equals("Fh")) onStep.commandBlind(":Fh#"); // move focuser to home (half travel) 40 | } 41 | 42 | } 43 | -------------------------------------------------------------------------------- /src/pages/focuser/HomeTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Focuser Home tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void focuserHomeTile(String &data); 10 | extern void focuserHomeTileAjax(String &data); 11 | extern void focuserHomeTileGet(); 12 | 13 | const char html_focuserHome[] PROGMEM = 14 | "" 16 | "    "; 18 | -------------------------------------------------------------------------------- /src/pages/focuser/SelectTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Focuser Select tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void focuserSelectTile(String &data); 10 | extern void focuserSelectTileAjax(String &data); 11 | extern void focuserSelectTileGet(); 12 | 13 | const char html_selectFocuser1[] PROGMEM = 14 | ""; 15 | const char html_selectFocuser2[] PROGMEM = 16 | ""; 17 | const char html_selectFocuser3[] PROGMEM = 18 | ""; 19 | const char html_selectFocuser4[] PROGMEM = 20 | ""; 21 | const char html_selectFocuser5[] PROGMEM = 22 | ""; 23 | const char html_selectFocuser6[] PROGMEM = 24 | ""; 25 | -------------------------------------------------------------------------------- /src/pages/htmlMessages.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include "Pages.common.h" 4 | 5 | const char html_bad_comms_message[] PROGMEM = 6 | "
" L_DOWN_TITLE "

" 7 | L_DOWN_MESSAGE1 L_DOWN_MESSAGE2 8 | "
  • " L_DOWN_MESSAGE3 "

  • " 9 | "
  • " L_DOWN_MESSAGE4 "

  • " 10 | "
  • " L_DOWN_MESSAGE5 "

  • " 11 | "
  • " L_DOWN_MESSAGE6 "

  • " 12 | "
  • " L_DOWN_MESSAGE7 "

  • " 13 | #if DISPLAY_RESET_CONTROLS != OFF 14 | "
    " 15 | "
    \n" 16 | #endif 17 | "

    \n"; 18 | -------------------------------------------------------------------------------- /src/pages/index/AmbientTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Ambient tile 3 | #include "AmbientTile.h" 4 | 5 | #include "../KeyValue.h" 6 | #include "../Pages.common.h" 7 | 8 | #if DISPLAY_WEATHER == ON 9 | 10 | // create the related webpage tile 11 | void ambientTile(String &data) 12 | { 13 | char temp[240] = ""; 14 | 15 | sprintf_P(temp, html_tile_text_beg, "22em", "11em", "Weather"); 16 | data.concat(temp); 17 | data.concat(F("

    ")); 18 | 19 | // Ambient conditions 20 | sprintf_P(temp, html_indexTPHD, L_AMBIENT_TEMPERATURE ":", 't', state.siteTemperatureStr); data.concat(temp); 21 | sprintf_P(temp, html_indexTPHD, L_PRESSURE ":", 'p', state.sitePressureStr); data.concat(temp); 22 | sprintf_P(temp, html_indexTPHD, L_HUMIDITY ":", 'h', state.siteHumidityStr); data.concat(temp); 23 | sprintf_P(temp, html_indexTPHD, L_DEW_POINT ":", 'd', state.siteDewPointStr); data.concat(temp); 24 | www.sendContentAndClear(data); 25 | 26 | data.concat(F("
    ")); 27 | 28 | data.concat(FPSTR(html_tile_end)); 29 | www.sendContentAndClear(data); 30 | 31 | } 32 | 33 | // use Ajax key/value pairs to pass related data to the web client in the background 34 | void ambientTileAjax(String &data) 35 | { 36 | data.concat(F("tphd_t|")); data.concat(state.siteTemperatureStr); data.concat("\n"); 37 | data.concat(F("tphd_p|")); data.concat(state.sitePressureStr); data.concat("\n"); 38 | data.concat(F("tphd_h|")); data.concat(state.siteHumidityStr); data.concat("\n"); 39 | data.concat(F("tphd_d|")); data.concat(state.siteDewPointStr); data.concat("\n"); 40 | 41 | www.sendContentAndClear(data); 42 | } 43 | 44 | // pass related data back to OnStep 45 | extern void ambientTileGet() 46 | { 47 | String v; 48 | } 49 | 50 | #endif 51 | -------------------------------------------------------------------------------- /src/pages/index/AmbientTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Ambient tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #if DISPLAY_WEATHER == ON 10 | 11 | extern void ambientTile(String &data); 12 | extern void ambientTileAjax(String &data); 13 | extern void ambientTileGet(); 14 | 15 | const char html_indexTPHD[] PROGMEM = "%s %s
    "; 16 | 17 | #endif 18 | -------------------------------------------------------------------------------- /src/pages/index/Index.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // The home page, status information 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #include "AmbientTile.h" 10 | #include "StatusTile.h" 11 | #include "AxisTile.h" 12 | #if DISPLAY_SERVO_MONITOR == ON 13 | #include "ServoTile.h" 14 | #endif 15 | #if DISPLAY_SERVO_CALIBRATION == ON 16 | #include "ServoCalibrateTile.h" 17 | #endif 18 | 19 | #if DRIVE_CONFIGURATION == ON 20 | const char html_configAxesNotes[] PROGMEM = 21 | "
    Notes:
      " 22 | "
    • " L_ADV_SET_FOOTER_MSG0 "
    • " 23 | "
    • " L_ADV_SET_FOOTER_MSG1 "
    • " 24 | "
    • " L_ADV_SET_FOOTER_MSG2 "
    • "; 25 | 26 | const char html_configAxesNotesOnStep[] PROGMEM = 27 | #if DRIVE_MAIN_AXES_CURRENT == ON 28 | "
    • " L_ADV_SET_FOOTER_MSG3 "
    • " 29 | #endif 30 | "
    • " L_ADV_SET_FOOTER_MSG4 "
    • " 31 | "
    "; 32 | #endif 33 | -------------------------------------------------------------------------------- /src/pages/index/StatusTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Controller Status tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void statusTile(String &data); 10 | extern void statusTileAjax(String &data); 11 | extern void statusTileGet(); 12 | 13 | const char html_indexGeneralError[] PROGMEM = L_LAST_GENERAL_ERROR ": %s
    \n"; 14 | 15 | const char html_indexWorkload[] PROGMEM = L_WORKLOAD ": %s
    \n"; 16 | 17 | #if DISPLAY_INTERNAL_TEMPERATURE == ON 18 | const char html_indexTemp[] PROGMEM = "%s %s
    "; 19 | #endif 20 | 21 | #if OPERATIONAL_MODE == WIFI 22 | const char html_indexSignalStrength[] PROGMEM = L_WIRELESS_SIGNAL_STRENGTH ": %s
    \n"; 23 | #endif 24 | 25 | const char html_indexMountType[] PROGMEM = 26 | L_PAGE_MOUNT L_ADV_MOUNT_TYPE ":
    " 27 | "

    \n"; 28 | 29 | const char html_resetNotes[] PROGMEM = 30 | "Notes:
      " 31 | "
    • " L_RESET_MSG1 "
    • " 32 | "
    • " L_DOWN_MESSAGE1 "
    • " 33 | "
    \n"; 34 | -------------------------------------------------------------------------------- /src/pages/mount/AlignTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Align tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void alignTile(String &data); 10 | extern void alignTileAjax(String &data); 11 | extern void alignTileGet(); 12 | 13 | const char html_alignCorrection[] PROGMEM = 14 | "%s  &  %s  (" L_ALIGN_MESSAGE " %s)

    "; 15 | 16 | const char html_alignStart[] PROGMEM = 17 | ""; 18 | 19 | const char html_alignAccept[] PROGMEM = 20 | "   "; 21 | 22 | const char html_alignRefine[] PROGMEM = 23 | L_REFINE_MESSAGE1 L_REFINE_MESSAGE2 "

    " L_REFINE_MESSAGE3 "

    " 24 | "" 25 | "
    "; 26 | -------------------------------------------------------------------------------- /src/pages/mount/GuideTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Guide tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void guideTile(String &data); 10 | extern void guideTileAjax(String &data); 11 | extern void guideTileGet(); 12 | 13 | const char html_guidePad[] PROGMEM = 14 | "
    " 15 | "" 16 | "" 17 | "
    " 18 | "
    "; 19 | 20 | const char html_guidePulseRates[] PROGMEM = 21 | "" 22 | "" 23 | "
    "; 24 | 25 | const char html_guideRates[] PROGMEM = 26 | "" 27 | "" 28 | "" 29 | "" 30 | "" 31 | "" 32 | "
    "; 33 | -------------------------------------------------------------------------------- /src/pages/mount/LimitsTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Limits and Backlash tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void limitsTile(String &data); 10 | extern void limitsTileAjax(String &data); 11 | extern void limitsTileGet(); 12 | 13 | // Misc 14 | const char html_configFormBegin[] PROGMEM = "

    \n
    "; 15 | const char html_configFormEnd[] PROGMEM = "\n

    \n

    \n"; 16 | 17 | // Overhead and Horizon limits 18 | const char html_configMinAlt[] PROGMEM = 19 | " " L_LIMITS_RANGE_HORIZON "
    \n"; 20 | 21 | const char html_configMaxAlt[] PROGMEM = 22 | " " L_LIMITS_RANGE_OVERHEAD "
    \n"; 23 | 24 | const char html_configBlAxis1[] PROGMEM = 25 | " " L_BACKLASH_RANGE_AXIS1 "
    \n"; 26 | 27 | const char html_configBlAxis2[] PROGMEM = 28 | " " L_BACKLASH_RANGE_AXIS2 "
    \n"; 29 | 30 | const char html_configPastMerE[] PROGMEM = 31 | " " L_LIMITS_RANGE_MERIDIAN_E "
    \n"; 32 | 33 | const char html_configPastMerW[] PROGMEM = 34 | " " L_LIMITS_RANGE_MERIDIAN_W "

    \n"; 35 | 36 | -------------------------------------------------------------------------------- /src/pages/mount/Mount.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Control 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #include "SiteTile.h" 10 | #include "HomeParkTile.h" 11 | #include "AlignTile.h" 12 | #include "GotoTile.h" 13 | #include "LibraryTile.h" 14 | #include "GuideTile.h" 15 | #include "TrackingTile.h" 16 | #include "PecTile.h" 17 | #include "LimitsTile.h" 18 | -------------------------------------------------------------------------------- /src/pages/mount/PecTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // PEC tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void pecTile(String &data); 10 | extern void pecTileAjax(String &data); 11 | extern void pecTileGet(); 12 | 13 | const char html_pecStatus[] PROGMEM = 14 | "
    " L_PEC_STATUS ":

    " 15 | "
    ?
    "; 16 | 17 | const char html_pecControls1[] PROGMEM = 18 | ""; 19 | 20 | const char html_pecControls2[] PROGMEM = 21 | "

    " 22 | "" 23 | "
    "; 24 | 25 | const char html_pecControls3[] PROGMEM = 26 | L_PEC_CLEAR_MESSAGE "
    "; 27 | 28 | const char html_pecControls4[] PROGMEM = 29 | "

    " L_PEC_EEWRITE_MESSAGE "
    "; 30 | -------------------------------------------------------------------------------- /src/pages/mount/SiteTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Date/Time/Location tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void siteTile(String &data); 10 | extern void siteTileAjax(String &data); 11 | extern void siteTileGet(); 12 | 13 | const char html_browserTime[] PROGMEM = 14 | " " L_TIME_BROWSER_UT 15 | "" 16 | "
    \n"; 17 | 18 | const char html_date[] PROGMEM = "%s"; 19 | const char html_time[] PROGMEM = " %s " L_UT; 20 | const char html_sidereal[] PROGMEM = " (%s  " L_LST ")
    "; 21 | const char html_site[] PROGMEM = 22 | L_LAT " %s
    " 23 | L_LONG " %s

    "; 24 | const char html_setDateTime[] PROGMEM = 25 | "
    \n" 26 | "
    " 27 | "" 28 | "
    \n" 29 | "" 30 | "\n" 31 | "
    \n"; 32 | 33 | const char html_longMsg[] PROGMEM = L_LOCATION_LONG ":
    \n"; 34 | const char html_latMsg[] PROGMEM = "
    " L_LOCATION_LAT ":
    \n"; 35 | const char html_offsetMsg[] PROGMEM = "
    " L_LOCATION_RANGE_UTC_OFFSET ":
    "; 36 | const char html_offsetMin[] PROGMEM = 37 | "  m\n"; 38 | const char html_offsetFooterMsg[] PROGMEM = "
    " L_LOCATION_MESSAGE_UTC_OFFSET "
    "; 39 | -------------------------------------------------------------------------------- /src/pages/rotator/BacklashTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Rotator Backlash tile 3 | #include "BacklashTile.h" 4 | 5 | #include "../KeyValue.h" 6 | #include "../Pages.common.h" 7 | 8 | // create the related webpage tile 9 | void rotatorBacklashTile(String &data) 10 | { 11 | char temp[240] = ""; 12 | char temp1[32] = ""; 13 | 14 | if (!onStep.command(":rb#", temp1)) strcpy(temp1, "0"); 15 | int backlash = atoi(temp1); 16 | 17 | sprintf_P(temp, html_tile_text_beg, "22em", "13em", "Backlash"); 18 | data.concat(temp); 19 | data.concat(F("

    ")); 20 | 21 | sprintf_P(temp, html_backlashValue, backlash); 22 | data.concat(temp); 23 | 24 | data.concat(F("
    ")); 25 | 26 | sprintf_P(temp, html_collapsable_beg, L_SETTINGS "..."); 27 | data.concat(temp); 28 | 29 | sprintf_P(temp, html_form_begin, "rotator.htm"); 30 | data.concat(temp); 31 | 32 | sprintf_P(temp, html_configBlAxis3, backlash); 33 | data.concat(temp); 34 | data.concat(F("\n")); 35 | 36 | data.concat(FPSTR(html_form_end)); 37 | www.sendContentAndClear(data); 38 | 39 | 40 | data.concat(FPSTR(html_collapsable_end)); 41 | data.concat(FPSTR(html_tile_end)); 42 | www.sendContentAndClear(data); 43 | } 44 | 45 | // use Ajax key/value pairs to pass related data to the web client in the background 46 | void rotatorBacklashTileAjax(String &data) 47 | { 48 | UNUSED(data); 49 | } 50 | 51 | // pass related data back to OnStep 52 | extern void rotatorBacklashTileGet() 53 | { 54 | String v; 55 | char temp[32] = ""; 56 | 57 | v = www.arg("b3"); 58 | if (!v.equals(EmptyStr)) { 59 | if (v.toInt() >= 0 && v.toInt() <= 32767) { 60 | sprintf(temp, ":rb%d#", (int16_t)v.toInt()); 61 | onStep.commandBool(temp); 62 | } 63 | } 64 | 65 | } 66 | -------------------------------------------------------------------------------- /src/pages/rotator/BacklashTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Rotator Backlash tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void rotatorBacklashTile(String &data); 10 | extern void rotatorBacklashTileAjax(String &data); 11 | extern void rotatorBacklashTileGet(); 12 | 13 | const char html_backlashValue[] PROGMEM = 14 | L_BACKLASH ": %d step(s)
    "; 15 | 16 | const char html_configBlAxis3[] PROGMEM = 17 | " " L_BACKLASH_RANGE_AXIS3UP "
    "; 18 | -------------------------------------------------------------------------------- /src/pages/rotator/DeRotatorTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // DeRotator tile 3 | #include "DeRotatorTile.h" 4 | 5 | #include "../KeyValue.h" 6 | #include "../Pages.common.h" 7 | 8 | // create the related webpage tile 9 | void deRotatorTile(String &data) 10 | { 11 | char temp[240] = ""; 12 | 13 | sprintf_P(temp, html_tile_beg, "22em", "13em", L_DEROTATOR); 14 | data.concat(temp); 15 | data.concat(F("

    ")); 16 | 17 | data.concat(FPSTR(html_controlDeRotate)); 18 | www.sendContentAndClear(data); 19 | 20 | data.concat(F("
    ")); 21 | 22 | data.concat(FPSTR(html_tile_end)); 23 | www.sendContentAndClear(data); 24 | } 25 | 26 | // use Ajax key/value pairs to pass related data to the web client in the background 27 | void deRotatorTileAjax(String &data) 28 | { 29 | if (status.mountType == MT_ALTAZM) { 30 | data.concat(keyValueToggleBoolSelected("rot_on", "rot_off", state.rotatorDerotate)); 31 | data.concat(keyValueBoolSelected("rot_rev", state.rotatorDerotateReverse)); 32 | www.sendContentAndClear(data); 33 | } 34 | } 35 | 36 | // pass related data back to OnStep 37 | extern void deRotatorTileGet() 38 | { 39 | String v; 40 | v = www.arg("rot"); 41 | if (!v.equals(EmptyStr)) 42 | { 43 | if (v.equals("off")) onStep.commandBlind(":r-#"); // disable derotator 44 | if (v.equals("on")) onStep.commandBlind(":r+#"); // enable derotator 45 | if (v.equals("rev")) onStep.commandBlind(":rR#"); // reverse rotator 46 | if (v.equals("par")) onStep.commandBlind(":rP#"); // move rotator to parallactic angle 47 | } 48 | 49 | } 50 | -------------------------------------------------------------------------------- /src/pages/rotator/DeRotatorTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // DeRotator tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void deRotatorTile(String &data); 10 | extern void deRotatorTileAjax(String &data); 11 | extern void deRotatorTileGet(); 12 | 13 | const char html_controlDeRotate[] PROGMEM = 14 | "" 15 | "
    " 16 | "
    " 17 | "
    "; 18 | -------------------------------------------------------------------------------- /src/pages/rotator/HomeTile.cpp: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Rotator Home tile 3 | #include "HomeTile.h" 4 | 5 | #include "../KeyValue.h" 6 | #include "../Pages.common.h" 7 | 8 | // create the related webpage tile 9 | void rotatorHomeTile(String &data) 10 | { 11 | char temp[240] = ""; 12 | 13 | sprintf_P(temp, html_tile_beg, "22em", "13em", L_HOMING); 14 | data.concat(temp); 15 | data.concat(F("

    ")); 16 | 17 | data.concat(FPSTR(html_rotatorHome)); 18 | 19 | data.concat(F("
    ")); 20 | 21 | data.concat(FPSTR(html_tile_end)); 22 | www.sendContentAndClear(data); 23 | } 24 | 25 | // use Ajax key/value pairs to pass related data to the web client in the background 26 | void rotatorHomeTileAjax(String &data) 27 | { 28 | UNUSED(data); 29 | } 30 | 31 | // pass related data back to OnStep 32 | extern void rotatorHomeTileGet() 33 | { 34 | String v; 35 | v = www.arg("rot"); 36 | if (!v.equals(EmptyStr)) 37 | { 38 | if (v.equals("reset")) onStep.commandBlind(":rF#"); // reset rotator at home 39 | if (v.equals("home")) onStep.commandBlind(":rC#"); // move rotator to home 40 | } 41 | } 42 | -------------------------------------------------------------------------------- /src/pages/rotator/HomeTile.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Rotator Home tile 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | extern void rotatorHomeTile(String &data); 10 | extern void rotatorHomeTileAjax(String &data); 11 | extern void rotatorHomeTileGet(); 12 | 13 | const char html_rotatorHome[] PROGMEM = 14 | "" 16 | ""; 18 | -------------------------------------------------------------------------------- /src/pages/rotator/Rotator.h: -------------------------------------------------------------------------------- 1 | // ----------------------------------------------------------------------------------- 2 | // Rotator 3 | #pragma once 4 | 5 | #include "../htmlHeaders.h" 6 | #include "../htmlMessages.h" 7 | #include "../htmlScripts.h" 8 | 9 | #include "HomeTile.h" 10 | #include "SlewingTile.h" 11 | #include "DeRotatorTile.h" 12 | #include "BacklashTile.h" 13 | -------------------------------------------------------------------------------- /src/pinmaps/Models.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Loads pinmap model for current configuration 3 | #pragma once 4 | 5 | #if defined(CONFIG_IDF_TARGET_ESP32S2) 6 | #include "Pins.Esp32S2.h" 7 | #define PINMAP_STR "ESP32-S2" 8 | 9 | #elif defined(CONFIG_IDF_TARGET_ESP32C3) 10 | #include "Pins.Esp32C3.h" 11 | #define PINMAP_STR "ESP32-C3" 12 | 13 | #elif defined(ESP32) 14 | #include "Pins.Esp32.h" 15 | #define PINMAP_STR "ESP32" 16 | 17 | #elif defined(ESP8266) 18 | #include "Pins.Esp8266.h" 19 | #define PINMAP_STR "ESP8266" 20 | 21 | #elif defined(__M0__) 22 | #include "Pins.M0.h" 23 | #define PINMAP_STR "ARDUINO M0" 24 | 25 | #elif defined(__TEENSYDUINO__) 26 | #include "Pins.Teensy.h" 27 | #define PINMAP_STR "TEENSY" 28 | 29 | #endif 30 | 31 | // all unassigned pins OFF 32 | #include "Pins.defaults.h" 33 | 34 | #if LED_STATUS_ON_STATE == HIGH 35 | #define LED_STATUS_OFF_STATE LOW 36 | #else 37 | #define LED_STATUS_OFF_STATE HIGH 38 | #endif 39 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.Esp32.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for ESP32 3 | #pragma once 4 | 5 | // locate WeMos D1 R32 serial port pins to match WeMos D1 Mini main and swapped port pins 6 | #ifndef SERIAL_ONSTEP 7 | #define SERIAL_ONSTEP Serial1 8 | #endif 9 | #ifndef SERIAL_RX 10 | #define SERIAL_RX 1 11 | #endif 12 | #ifndef SERIAL_TX 13 | #define SERIAL_TX 3 14 | #endif 15 | #ifndef SERIAL_SWAPPED_RX 16 | #define SERIAL_SWAPPED_RX 23 17 | #endif 18 | #ifndef SERIAL_SWAPPED_TX 19 | #define SERIAL_SWAPPED_TX 5 20 | #endif 21 | 22 | #ifndef LED_STATUS_PIN 23 | #define LED_STATUS_PIN 2 // pin 2 is a guess and is probably wrong 24 | #endif 25 | 26 | #define BOOT0_PIN 5 // GPIO5 to Boot0 of STM32 etc. (no swapped serial if active) 27 | 28 | #define ETHERNET_CS_PIN 27 // pin# for W5500 chip select 29 | #define ETHERNET_RESET_PIN 26 // pin# for controlling the reset of W5500 so it comes up properly 30 | 31 | #define AXIS1_ENCODER_A_PIN 18 // pin# for Axis1 encoder, for A or CW or MA/CLK 32 | #define AXIS1_ENCODER_B_PIN 19 // pin# for Axis1 encoder, for B or CCW or SLO 33 | #define AXIS2_ENCODER_A_PIN 22 // pin# for Axis2 encoder, for A or CW or MA/CLK 34 | #define AXIS2_ENCODER_B_PIN 21 // pin# for Axis2 encoder, for B or CCW or SLO 35 | 36 | #if AXIS1_ENCODER == OFF || AXIS2_ENCODER == OFF 37 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 38 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 39 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 40 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 41 | #endif 42 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.Esp32c3.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for ESP32C3 LilyGO T-01C3 (experimental) 3 | #pragma once 4 | 5 | // locate ESP32-C3 serial port pins 6 | #ifndef SERIAL_ONSTEP 7 | #define SERIAL_ONSTEP Serial1 8 | #endif 9 | #ifndef SERIAL_RX 10 | #define SERIAL_RX 20 11 | #endif 12 | #ifndef SERIAL_TX 13 | #define SERIAL_TX 21 14 | #endif 15 | #ifndef SERIAL_SWAPPED_RX 16 | #define SERIAL_SWAPPED_RX OFF 17 | #endif 18 | #ifndef SERIAL_SWAPPED_TX 19 | #define SERIAL_SWAPPED_TX OFF 20 | #endif 21 | 22 | #ifndef LED_STATUS_PIN 23 | #define LED_STATUS_PIN 3 24 | #endif 25 | 26 | #define BOOT0_PIN OFF // to Boot0 of STM32 etc. (no swapped serial if active) 27 | 28 | #define ETHERNET_RESET_PIN OFF // pin# for controlling the reset of W5500 so it comes up properly 29 | #define SD_CARD_CS_PIN OFF // pin 4 to CS for SD adapter on Arduino Ethernet Shield 30 | 31 | #define AXIS1_ENCODER_A_PIN OFF // pin# for Axis1 encoder, for A or CW or MA/CLK 32 | #define AXIS1_ENCODER_B_PIN OFF // pin# for Axis1 encoder, for B or CCW or SLO 33 | #define AXIS2_ENCODER_A_PIN OFF // pin# for Axis1 encoder, for A or CW or MA/CLK 34 | #define AXIS2_ENCODER_B_PIN OFF // pin# for Axis1 encoder, for B or CCW or SLO 35 | 36 | #if AXIS1_ENCODER == OFF || AXIS2_ENCODER == OFF 37 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 38 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 39 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 40 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 41 | #endif 42 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.Esp32s2.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for ESP32S2 3 | #pragma once 4 | 5 | // locate ESP32-S2 serial port pins 6 | #ifndef SERIAL_ONSTEP 7 | #define SERIAL_ONSTEP Serial1 8 | #endif 9 | #ifndef SERIAL_RX 10 | #define SERIAL_RX 11 11 | #endif 12 | #ifndef SERIAL_TX 13 | #define SERIAL_TX 12 14 | #endif 15 | #ifndef SERIAL_SWAPPED_RX 16 | #define SERIAL_SWAPPED_RX 12 17 | #endif 18 | #ifndef SERIAL_SWAPPED_TX 19 | #define SERIAL_SWAPPED_TX 11 20 | #endif 21 | 22 | #ifndef LED_STATUS_PIN 23 | #define LED_STATUS_PIN 15 // Change in config.h if needed 24 | #endif 25 | 26 | #define BOOT0_PIN 5 // GPIO5 to Boot0 of STM32 etc. (no swapped serial if active) 27 | 28 | #define ETHERNET_RESET_PIN 9 // pin# for controlling the reset of W5500 so it comes up properly 29 | #define SD_CARD_CS_PIN OFF // pin 4 to CS for SD adapter on Arduino Ethernet Shield 30 | 31 | #define AXIS1_ENCODER_A_PIN 7 // pin# for Axis1 encoder, for A or CW or MA/CLK 32 | #define AXIS1_ENCODER_B_PIN 9 // pin# for Axis1 encoder, for B or CCW or SLO 33 | #define AXIS2_ENCODER_A_PIN 35 // pin# for Axis1 encoder, for A or CW or MA/CLK 34 | #define AXIS2_ENCODER_B_PIN 33 // pin# for Axis1 encoder, for B or CCW or SLO 35 | 36 | #if AXIS1_ENCODER == OFF || AXIS2_ENCODER == OFF 37 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 38 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 39 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 40 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 41 | #endif 42 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.Esp8266.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for ESP8266 3 | #pragma once 4 | 5 | // Standard WeMos D1 Mini serial port 6 | #ifndef SERIAL_ONSTEP 7 | #define SERIAL_ONSTEP Serial 8 | #endif 9 | 10 | #ifndef LED_STATUS_PIN 11 | #define LED_STATUS_PIN 2 // pin GPIO2 is the status led 12 | #endif 13 | 14 | #define BOOT0_PIN 15 // pin D8, GPIO15 to Boot0 of STM32 etc. (no swapped serial if active) 15 | 16 | #define ETHERNET_RESET_PIN D2 // pin# for controlling the reset of W5500 so it comes up properly 17 | #define ETHERNET_CS_PIN D1 // pin# for W5500 SPI CS 18 | #define SD_CARD_CS_PIN OFF // pin 4 to CS for SD adapter on Arduino Ethernet Shield 19 | 20 | #define AXIS1_ENCODER_A_PIN 14 // pin# for Axis1 encoder, for A or CW or MA/CLK 21 | #define AXIS1_ENCODER_B_PIN 12 // pin# for Axis1 encoder, for B or CCW or SLO 22 | #define AXIS2_ENCODER_A_PIN 5 // pin# for Axis2 encoder, for A or CW or MA/CLK 23 | #define AXIS2_ENCODER_B_PIN 4 // pin# for Axis2 encoder, for B or CCW or SLO 24 | 25 | #if AXIS1_ENCODER == OFF || AXIS2_ENCODER == OFF 26 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 27 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 28 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 29 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 30 | #endif 31 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.M0.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for Arduino M0 3 | #pragma once 4 | 5 | #ifndef SERIAL_ONSTEP 6 | #define SERIAL_ONSTEP Serial1 7 | #endif 8 | 9 | #ifndef LED_STATUS_PIN 10 | #define LED_STATUS_PIN 13 // pin 13 is probably the status led, a guess 11 | #endif 12 | 13 | #define BOOT0_PIN 10 // pin 10 to Boot0 of STM32 etc. 14 | 15 | #define ETHERNET_RESET_PIN 9 // pin# for controlling the reset of W5500 so it comes up properly 16 | 17 | #define AXIS1_ENCODER_A_PIN 5 // pin# for Axis1 encoder, for A or CW or MA/CLK 18 | #define AXIS1_ENCODER_B_PIN 6 // pin# for Axis1 encoder, for B or CCW or SLO 19 | #define AXIS2_ENCODER_A_PIN 7 // pin# for Axis2 encoder, for A or CW or MA/CLK 20 | #define AXIS2_ENCODER_B_PIN 8 // pin# for Axis2 encoder, for B or CCW or SLO 21 | 22 | #if AXIS1_ENCODER == OFF || AXIS2_ENCODER == OFF 23 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 24 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 25 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 26 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 27 | #endif 28 | 29 | #define SD_CARD_CS_PIN 4 // pin 4 to CS for SD adapter on Arduino Ethernet Shield 30 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.Teensy.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Pin map for Teensy 3.0, 3.1, 3.2, 3.5, 3.6, 4.0, 4.1 3 | #pragma once 4 | 5 | #ifndef SERIAL_ONSTEP 6 | #define SERIAL_ONSTEP Serial1 7 | #endif 8 | 9 | #define BOOT0_PIN 4 // pin 4, to Boot0 of STM32 etc. 10 | 11 | #define AXIS1_ENCODER_A_PIN 5 // pin# for Axis1 encoder, for A or CW 12 | #define AXIS1_ENCODER_B_PIN 6 // pin# for Axis1 encoder, for B or CCW 13 | #define AXIS2_ENCODER_A_PIN 7 // pin# for Axis2 encoder, for A or CW 14 | #define AXIS2_ENCODER_B_PIN 8 // pin# for Axis2 encoder, for B or CCW 15 | 16 | #if AXIS1_ENCODER > 0 && AXIS2_ENCODER > 0 17 | #define VGPIO_PIN_0 OFF 18 | #define VGPIO_PIN_1 OFF 19 | #define VGPIO_PIN_2 OFF 20 | #define VGPIO_PIN_3 OFF 21 | #else 22 | #define VGPIO_PIN_0 AXIS1_ENCODER_A_PIN 23 | #define VGPIO_PIN_1 AXIS1_ENCODER_B_PIN 24 | #define VGPIO_PIN_2 AXIS2_ENCODER_A_PIN 25 | #define VGPIO_PIN_3 AXIS2_ENCODER_B_PIN 26 | #endif 27 | 28 | #define ETHERNET_RESET_PIN 9 // pin# for controlling the reset of W5500 so it comes up properly 29 | 30 | #define LED_STATUS_PIN 13 // pin 13 is the status led 31 | 32 | #define SD_CARD_CS_PIN OFF // pin 4 to CS for SD adapter on Arduino Ethernet Shield 33 | -------------------------------------------------------------------------------- /src/pinmaps/Pins.defaults.h: -------------------------------------------------------------------------------- 1 | // ------------------------------------------------------------------------------------------------- 2 | // Default pin assignments 3 | #pragma once 4 | 5 | // serial interface defaults 6 | #ifndef SERIAL_RX 7 | #define SERIAL_RX OFF 8 | #endif 9 | #ifndef SERIAL_TX 10 | #define SERIAL_TX OFF 11 | #endif 12 | #ifndef SERIAL_SWAPPED_RX 13 | #define SERIAL_SWAPPED_RX OFF 14 | #endif 15 | #ifndef SERIAL_SWAPPED_TX 16 | #define SERIAL_SWAPPED_TX OFF 17 | #endif 18 | 19 | // status indication 20 | #ifndef LED_STATUS_PIN 21 | #define LED_STATUS_PIN OFF 22 | #endif 23 | 24 | // pin to force OnStep MCU into upload mode on reset 25 | #ifndef BOOT0_PIN 26 | #define BOOT0_PIN OFF 27 | #endif 28 | 29 | // ethernet control 30 | #ifndef ETHERNET_CS_PIN 31 | #define ETHERNET_CS_PIN OFF 32 | #endif 33 | #ifndef ETHERNET_RESET_PIN 34 | #define ETHERNET_RESET_PIN OFF 35 | #endif 36 | #ifndef SD_CARD_CS_PIN 37 | #define SD_CARD_CS_PIN OFF 38 | #endif 39 | 40 | // encoders 41 | #ifndef AXIS1_ENCODER_A_PIN 42 | #define AXIS1_ENCODER_A_PIN OFF 43 | #endif 44 | #ifndef AXIS1_ENCODER_B_PIN 45 | #define AXIS1_ENCODER_B_PIN OFF 46 | #endif 47 | #ifndef AXIS2_ENCODER_A_PIN 48 | #define AXIS2_ENCODER_A_PIN OFF 49 | #endif 50 | #ifndef AXIS2_ENCODER_B_PIN 51 | #define AXIS2_ENCODER_B_PIN OFF 52 | #endif 53 | 54 | // virtual GPIO control 55 | #ifndef VGPIO_PIN_0 56 | #define VGPIO_PIN_0 OFF 57 | #endif 58 | #ifndef VGPIO_PIN_1 59 | #define VGPIO_PIN_1 OFF 60 | #endif 61 | #ifndef VGPIO_PIN_2 62 | #define VGPIO_PIN_2 OFF 63 | #endif 64 | #ifndef VGPIO_PIN_3 65 | #define VGPIO_PIN_3 OFF 66 | #endif 67 | #ifndef VGPIO_PIN_4 68 | #define VGPIO_PIN_4 OFF 69 | #endif 70 | #ifndef VGPIO_PIN_5 71 | #define VGPIO_PIN_5 OFF 72 | #endif 73 | #ifndef VGPIO_PIN_6 74 | #define VGPIO_PIN_6 OFF 75 | #endif 76 | #ifndef VGPIO_PIN_7 77 | #define VGPIO_PIN_7 OFF 78 | #endif 79 | -------------------------------------------------------------------------------- /src/pinmaps/pinmaps.ino: -------------------------------------------------------------------------------- 1 | // Placeholder file 2 | // Nothing to see here ... 3 | // 4 | // This file is only present so the Arduino IDE can edit the .h file(s) 5 | --------------------------------------------------------------------------------