├── .gitignore ├── .travis.yml ├── Doxyfile ├── LICENSE ├── README.md ├── firmware.md ├── hardware ├── 3dprint │ ├── GM37-BLDC3650 mount bottom.zip │ ├── GM37-BLDC3650 mount top.zip │ ├── Liam XD-3420 mount.zip │ ├── Liam cutter mount.zip │ ├── Liam main board.zip │ ├── Liam wheel mount.zip │ ├── README.md │ └── XD-3420.zip ├── ADS1115.pdf ├── DS_IM120628012_HC_SR04.pdf ├── E28-2G4M12S_Usermanual_EN_v1.5.pdf ├── MCP23017.pdf ├── README.md ├── SX1280-Semtech.pdf ├── battery.md ├── gnss.md ├── lora-radio.md ├── motors.md └── schematic │ ├── Liam power-pcb.json │ ├── liam-logic-pcb.json │ ├── liam-logic-pcb.svg │ ├── liam-logic-sch.json │ ├── liam-logic-sch.pdf │ ├── liam-power-pcb.svg │ ├── liam-power-sch.json │ └── liam-power-sch.pdf ├── lib └── readme.txt ├── notes ├── platformio.ini ├── run_coverage.sh ├── src ├── battery.cpp ├── battery.h ├── configuration.cpp ├── configuration.h ├── cutter.cpp ├── cutter.h ├── definitions.cpp ├── definitions.h ├── dockingstation │ ├── dockingstation.cpp │ ├── dockingstation.h │ ├── sign_on.proto │ ├── sign_on_resp.proto │ ├── status.proto │ └── system.proto ├── gps.cpp ├── gps.h ├── io_accelerometer │ ├── io_accelerometer.cpp │ ├── io_accelerometer.h │ ├── madgwick_filters.cpp │ └── madgwick_filters.h ├── io_analog.cpp ├── io_analog.h ├── io_digital.cpp ├── io_digital.h ├── log_store.cpp ├── log_store.h ├── lora.cpp ├── main.cpp ├── mowing_schedule.cpp ├── mowing_schedule.h ├── processable.h ├── resources.h ├── scheduler │ ├── scheduler.cpp │ └── scheduler.h ├── sonar.cpp ├── sonar.h ├── state_controller.cpp ├── state_controller.h ├── states │ ├── abstract_state.h │ ├── charging.cpp │ ├── charging.h │ ├── docked.cpp │ ├── docked.h │ ├── docking.cpp │ ├── docking.h │ ├── flipped.cpp │ ├── flipped.h │ ├── launching.cpp │ ├── launching.h │ ├── manual.cpp │ ├── manual.h │ ├── mowing.cpp │ ├── mowing.h │ ├── stop.cpp │ ├── stop.h │ ├── stuck.cpp │ ├── stuck.h │ ├── test.cpp │ └── test.h ├── utils.cpp ├── utils.h ├── vector.h ├── wheel.cpp ├── wheel.h ├── wheel_controller.cpp └── wheel_controller.h ├── test └── liam-esp.postman_collection.json └── web ├── .eslintignore ├── .eslintrc ├── .stylelintrc ├── build └── webpack.config.js ├── liam-esp@1.0.0 ├── mock ├── api-mocker.js ├── mock-data.js ├── moveSequence.json └── socket-mocker.js ├── package-lock.json ├── package.json ├── patches └── reconnecting-websocket+4.1.10.patch └── src ├── api.js ├── authorisation.js ├── components └── joystick.js ├── favicons ├── android-chrome-192x192.png ├── android-chrome-512x512.png ├── apple-touch-icon-120x120.png ├── apple-touch-icon-152x152.png ├── apple-touch-icon-180x180.png ├── apple-touch-icon-60x60.png ├── apple-touch-icon-76x76.png ├── apple-touch-icon.png ├── browserconfig.xml ├── favicon-16x16.png ├── favicon-32x32.png ├── favicon.ico ├── mstile-150x150.png ├── safari-pinned-tab.svg └── site.webmanifest ├── html ├── index.ejs └── swagger │ ├── swagger.html │ └── swagger.yaml ├── index.js ├── maputils.js ├── resources ├── 3d_mower.blend ├── 3d_mower.glb ├── battery.svg ├── body.fbx ├── disc.fbx ├── guide.fbx ├── housing.fbx ├── panel_1.jpg ├── panel_2.jpg └── wheel.fbx ├── sections ├── info.js ├── manual.js ├── map.js ├── metrics.js ├── schedule.js ├── settings.js └── start.js └── styles └── main.scss /.gitignore: -------------------------------------------------------------------------------- 1 | .pio 2 | .pioenvs 3 | .piolibdeps 4 | .clang_complete 5 | .gcc-flags.json 6 | .vscode 7 | .vscode/.browse.c_cpp.db* 8 | .vscode/c_cpp_properties.json 9 | .vscode/launch.json 10 | web/node_modules 11 | data 12 | -------------------------------------------------------------------------------- /.travis.yml: -------------------------------------------------------------------------------- 1 | # Continuous Integration (CI) is the practice, in software 2 | # engineering, of merging all developer working copies with a shared mainline 3 | # several times a day < http://docs.platformio.org/page/ci/index.html > 4 | # 5 | # Documentation: 6 | # 7 | # * Travis CI Embedded Builds with PlatformIO 8 | # < https://docs.travis-ci.com/user/integration/platformio/ > 9 | # 10 | # * PlatformIO integration with Travis CI 11 | # < http://docs.platformio.org/page/ci/travis.html > 12 | # 13 | # * User Guide for `platformio ci` command 14 | # < http://docs.platformio.org/page/userguide/cmd_ci.html > 15 | # 16 | 17 | language: python 18 | python: 19 | - "2.7" 20 | 21 | sudo: false 22 | cache: 23 | directories: 24 | - "~/.platformio" 25 | 26 | # update Makefile if target boards added 27 | env: 28 | global: 29 | - CXX=g++-5 30 | #- PLATFORMIO_BOARD=uno 31 | - PLATFORMIO_BOARD=nodemcuv2 32 | 33 | addons: 34 | apt: 35 | sources: 36 | - ubuntu-toolchain-r-test 37 | packages: 38 | - g++-5 39 | - lcov 40 | - doxygen 41 | - doxygen-doc 42 | - doxygen-latex 43 | - doxygen-gui 44 | - graphviz 45 | - cppcheck 46 | 47 | install: 48 | - pip install -U platformio 49 | #- platformio lib install 44 50 | 51 | script: 52 | - platformio run 53 | # Build and run unit tests 54 | #- bash test/run_tests.sh 55 | # Run static code analysis over the source code 56 | - cppcheck --std=c++11 --enable=performance,portability,information --quiet --error-exitcode=1 src/ 57 | #- platformio ci --lib="." --board=nodemcuv2 58 | 59 | after_success: 60 | - bash run_coverage.sh 61 | # Upload report to codecov 62 | #- bash <(curl -s https://codecov.io/bash) -s coverage-reports || echo "Codecov did not collect coverage reports" 63 | # Generate documentation 64 | - doxygen Doxyfile 65 | 66 | notifications: 67 | email: false 68 | 69 | slack: 70 | rooms: 71 | secure: 72 | on_failure: always 73 | on_success: change 74 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2017 Henrik Östman 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Liam-ESP 2 | 3 | [![license](https://img.shields.io/github/license/trycoon/liam-esp.svg?maxAge=3600)](https://opensource.org/licenses/MIT) 4 | 5 | ## Introduction 6 | 7 | _A project for building your own robotic lawn mower._ 8 | 9 | The concept and basic ideas are sprung from the ["Liam lawn mower"](https://github.com/sm6yvr/liam) and [ArduMower](https://www.ardumower.de/index.php/en/) projects, but instead of using an Arduino for controlling the mower this project makes use of the more powerful "Espressif ESP32" microcontroller. The ESP32 boosts more CPU power and memory than a average Arduino, leaving us with less limits but still at a low price. 10 | 11 | Here are some of the features of this project: 12 | 13 | - Automatic mowing of lawn using a two wheeled robot. 14 | - GNSS-RTK navigation support, for accurate mowing and path planning. 15 | - WiFi connected docking station that relays communication to mower over a LoRa-connection. 16 | - Easy to use REST-based API with Swagger support, making it a breeze to integrate with Home automation softwares. 17 | - Monitor mower using [MQTT protocol](documentation/api.md) (works with most Home automation systems). 18 | - Realtime monitoring using Websocket. 19 | - Built in support for scheduled mowing (time of day, days of week). 20 | - Obstacle avoidance using ultrasound transducers. 21 | - Support accelerometer, gyroscope, and e-compass to keep mower on a straight line, and detect if mower has flipped over (safety reasons). 22 | - Integrated Web UI in docking station for controlling and monitoring mower, see [demo site](http://liam.smart-home.rocks/). (username: admin, password: liam) 23 | 24 | **This repository only contains hardware schematics and firmware for the mower, the [docking station has its own project](https://github.com/trycoon/liam-dockingstation)!** 25 | 26 | ### -> [Building the mower body](hardware/3dprint/README.md) 27 | 28 | ### -> [Building the electronics](hardware/README.md) 29 | 30 | ### -> [Building the firmware](firmware.md) 31 | 32 | ## License & Author 33 | 34 | ``` 35 | MIT License 36 | 37 | Copyright (c) 2017 Henrik Östman 38 | 39 | Permission is hereby granted, free of charge, to any person obtaining a copy 40 | of this software and associated documentation files (the "Software"), to deal 41 | in the Software without restriction, including without limitation the rights 42 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 43 | copies of the Software, and to permit persons to whom the Software is 44 | furnished to do so, subject to the following conditions: 45 | 46 | The above copyright notice and this permission notice shall be included in all 47 | copies or substantial portions of the Software. 48 | 49 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 50 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 51 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 52 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 53 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 54 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 55 | SOFTWARE 56 | ``` 57 | -------------------------------------------------------------------------------- /firmware.md: -------------------------------------------------------------------------------- 1 | ## Build and upload firmware 2 | 3 | To simplify building the firmware, with all its dependencies, we use the [Platform.io](https://platformio.org/) open source ecosystem. Make sure you have Platform.io installed on your computer before you proceed. 4 | 5 | ### Compile and upload the Liam-ESP application 6 | 7 | Connect a micro-USB cable between your computer and the ESP32 microcontroller, run the following command in the root folder of this project to compile and upload the software to the ESP32: 8 | 9 | ``` 10 | platformio run -t upload 11 | ``` 12 | 13 | If your computer is stuck waiting on the following line: 14 | 15 | ``` 16 | Serial port /dev/ttyUSB0 17 | ``` 18 | 19 | and eventually timing out, then you need to press the "flash"-button on the ESP32 for 2-3 seconds when waiting on those lines to initialize the flashing-process! 20 | 21 | ## Debugging and faultfinding 22 | 23 | ### Error decoding 24 | 25 | xtensa-esp32-elf-addr2line -pfiaC -e build/PROJECT.elf ADDRESS 26 | -------------------------------------------------------------------------------- /hardware/3dprint/GM37-BLDC3650 mount bottom.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/GM37-BLDC3650 mount bottom.zip -------------------------------------------------------------------------------- /hardware/3dprint/GM37-BLDC3650 mount top.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/GM37-BLDC3650 mount top.zip -------------------------------------------------------------------------------- /hardware/3dprint/Liam XD-3420 mount.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/Liam XD-3420 mount.zip -------------------------------------------------------------------------------- /hardware/3dprint/Liam cutter mount.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/Liam cutter mount.zip -------------------------------------------------------------------------------- /hardware/3dprint/Liam main board.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/Liam main board.zip -------------------------------------------------------------------------------- /hardware/3dprint/Liam wheel mount.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/Liam wheel mount.zip -------------------------------------------------------------------------------- /hardware/3dprint/README.md: -------------------------------------------------------------------------------- 1 | TBD 2 | -------------------------------------------------------------------------------- /hardware/3dprint/XD-3420.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/3dprint/XD-3420.zip -------------------------------------------------------------------------------- /hardware/ADS1115.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/ADS1115.pdf -------------------------------------------------------------------------------- /hardware/DS_IM120628012_HC_SR04.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/DS_IM120628012_HC_SR04.pdf -------------------------------------------------------------------------------- /hardware/E28-2G4M12S_Usermanual_EN_v1.5.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/E28-2G4M12S_Usermanual_EN_v1.5.pdf -------------------------------------------------------------------------------- /hardware/MCP23017.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/MCP23017.pdf -------------------------------------------------------------------------------- /hardware/SX1280-Semtech.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/SX1280-Semtech.pdf -------------------------------------------------------------------------------- /hardware/battery.md: -------------------------------------------------------------------------------- 1 | 2 | ## Li-ion batteries 3 | 4 | The mower could be run on a variety of batteries, from lead-acid to lithium polymer (LiPo), but lithium-ion (Li-ion) batteries could be the sweet spot. Li-ion batteries are lighter and can store more energy than lead-acid and are cheeper and safer than Li-Po batteries. 5 | 6 | You could buy [ready made battery packs](https://www.google.com/search?q=li-ion+battery+pack+%2B14.4v) on the Internet, but it is also possible to make your [own battery packs](https://www.youtube.com/watch?v=NGp7cGBYOLc) (if unsure, don't do it!). Either way the battery pack should be able to deliver at least 4 ampere continually and 6 ampere temporally to support the power hungry motors in the mower. It is also important that the battery pack is equipped with a protective circuit for overcharge, over-discharge and short circuit! 7 | 8 | Read up on [Li-ion functionality](http://batteryuniversity.com/learn/article/types_of_lithium_ion). 9 | 10 | If you take on the quest to build your own battery pack, then these battery cells could be suitable [Samsung INR18650-15M](https://secondlifestorage.com/t-Samsung-INR18650-15M-Cell-Specifications) and [Samsung INR18650-30Q](https://secondlifestorage.com/t-Samsung-INR18650-30Q-Cell-Specifications). 11 | 12 | ## Balancer Management System (BMS) cards for Li-ion batteries 13 | 14 | For optimal use the battery packs should be fitted with a [BMS-card](https://en.wikipedia.org/wiki/Battery_management_system) to protect the cells and help balancing cells during charge-phase. 15 | 16 | Suitable BMS-cards: 17 | 18 | * ["cf-4s30a-a"](https://www.google.com/search?q=cf-4s30a-a), more information about the charger [here](https://mysku.me/blog/aliexpress/58000.html) (in Russia). 19 | * [yh2204a](https://www.google.com/search?q=yh2204a) 20 | * [Smart BMS](https://www.lithiumbatterypcb.com/product-instructionev-battery-pcb-boardev-battery-pcb-board/ev-battery-pcb-board/smart-bms-of-power-battery/) -------------------------------------------------------------------------------- /hardware/gnss.md: -------------------------------------------------------------------------------- 1 | GNSS module with centimeter precision: 2 | https://learn.sparkfun.com/tutorials/gps-rtk2-hookup-guide 3 | 4 | A suitable antenna: 5 | https://www.sparkfun.com/products/15192 6 | 7 | Optional ground plane for increased antenna performance (or find a thick steel disc in your workshop): 8 | https://www.sparkfun.com/products/15004 -------------------------------------------------------------------------------- /hardware/lora-radio.md: -------------------------------------------------------------------------------- 1 | LoRa (Long Range) is a radio modulation technique owned and developed by the Semtech company. They develop the popular [SX127\* radio modems](https://www.semtech.com/products/wireless-rf/lora-transceivers/SX1278) that offers a very long range (tens of kilometers) radio link, but with a very low bitrate (tens of kbps). 2 | 3 | We use two LoRa modems, one in the mower and the other in the docking station. They are used for relaying request from the clients through the docking station to the mower, and for reporting mower status back to docking station and the clients. LoRa offers connections over a greater distance with higher reliability than ordinary WiFi (IEEE 802.11). 4 | 5 | There are plenty of suitable LoRa modems out there, these are two common examples: 6 | 7 | - ["Winext LM1278"](https://www.google.com/search?q=Winext+LM1278) 8 | - ["AI-Thinker RA-02"](https://www.google.com/search?q=AI-Thinker+RA-02) 9 | 10 | Remember to buy TWO of them, one for mower and one for docking station. Also make sure you select the [correct frequency for you country](https://www.thethingsnetwork.org/docs/lorawan/frequencies-by-country.html)! 11 | If no antenna is included you have to buy TWO antennas for the matching frequency. 12 | 13 | AND NEVER START THE MODULE WITHOUT THE ANTENNA CONNECTED (it will damage the modem)! 14 | 15 | [SX1278 datasheets](sx1276_77_78_79.pdf) 16 | -------------------------------------------------------------------------------- /hardware/motors.md: -------------------------------------------------------------------------------- 1 | ## Wheel motor 2 | "GM37-BLDC3650", 12/24V 3.1A (max) 3 | 4 | "36GP-BLDC3650" (same motor, better gearbox) 5 | 6 | ## Cutter motor 7 | 8 | "Guang Wan XD-3420", 12V 30W 3.1A (max) -------------------------------------------------------------------------------- /hardware/schematic/liam-logic-sch.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/schematic/liam-logic-sch.pdf -------------------------------------------------------------------------------- /hardware/schematic/liam-power-sch.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/hardware/schematic/liam-power-sch.pdf -------------------------------------------------------------------------------- /lib/readme.txt: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for the project specific (private) libraries. 3 | PlatformIO will compile them to static libraries and link to executable file. 4 | 5 | The source code of each library should be placed in separate directory, like 6 | "lib/private_lib/[here are source files]". 7 | 8 | For example, see how can be organized `Foo` and `Bar` libraries: 9 | 10 | |--lib 11 | | |--Bar 12 | | | |--docs 13 | | | |--examples 14 | | | |--src 15 | | | |- Bar.c 16 | | | |- Bar.h 17 | | |--Foo 18 | | | |- Foo.c 19 | | | |- Foo.h 20 | | |- readme.txt --> THIS FILE 21 | |- platformio.ini 22 | |--src 23 | |- main.c 24 | 25 | Then in `src/main.c` you should use: 26 | 27 | #include 28 | #include 29 | 30 | // rest H/C/CPP code 31 | 32 | PlatformIO will find your libraries automatically, configure preprocessor's 33 | include paths and build them. 34 | 35 | More information about PlatformIO Library Dependency Finder 36 | - http://docs.platformio.org/page/librarymanager/ldf.html 37 | -------------------------------------------------------------------------------- /notes: -------------------------------------------------------------------------------- 1 | Useful stuff, inspiration and so forth 2 | 3 | https://bitbucket.org/xoseperez/espurna/src/master/ 4 | -------------------------------------------------------------------------------- /platformio.ini: -------------------------------------------------------------------------------- 1 | ; PlatformIO Project Configuration File 2 | ; 3 | ; Build options: build flags, source filter 4 | ; Upload options: custom upload port, speed and extra flags 5 | ; Library options: dependencies, extra library storages 6 | ; Advanced options: extra scripting 7 | ; 8 | ; Please visit documentation for the other options and examples 9 | ; http://docs.platformio.org/page/projectconf.html 10 | 11 | [env:nodemcuv2] 12 | platform = espressif32 13 | board = nodemcu-32s 14 | framework = arduino 15 | monitor_speed = 115200 16 | upload_speed = 921600 17 | debug_tool = jlink 18 | ; https://docs.platformio.org/en/latest/plus/debug-tools/jlink.html 19 | ; https://gojimmypi.blogspot.com/2017/05/vscode-jtag-debugging-of-esp32-part-1.html 20 | ; JTAG interface 21 | ; upload_protocol = jlink-jtag 22 | ;targets = upload, monitor 23 | 24 | ;[env:nodemcuv2_upstream_develop] 25 | ;platform = https://github.com/platformio/platform-espressif32.git 26 | ;board = nodemcu-32s 27 | ;framework = arduino 28 | ;monitor_speed = 115200 29 | ;upload_speed = 921600 30 | ;debug_tool = jlink 31 | 32 | ;[env:esp32thing] 33 | ;platform = espressif32 34 | ;board = esp32thing 35 | ;framework = arduino 36 | ;monitor_speed = 115200 37 | ;upload_speed = 921600 38 | ;targets = upload, monitor 39 | 40 | ; OTA flashing 41 | ;upload_port = 42 | ;upload_flags = --auth= 43 | 44 | lib_deps = 45 | ArduinoLog=https://github.com/thijse/Arduino-Log.git#49934a54f7ecdd9ba3c831e6f6930028cfcb2bb1 46 | SparkFun Ublox Arduino Library@1.6.0 47 | SparkFun LSM9DS1 IMU@1.2.0 48 | Adafruit ADS1X15=https://github.com/soligen2010/Adafruit_ADS1X15.git#7d67b451f739e9a63f40f2d6d139ab582258572b 49 | 6001@1.1.2 ;https://github.com/blemasle/arduino-mcp23017 50 | Nanopb@0.3.9.2 51 | LoRaLib@8.1.1 -------------------------------------------------------------------------------- /run_coverage.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | caller_dir=$PWD 3 | 4 | coverage_report_dir="${TRAVIS_BUILD_DIR}/coverage-reports" 5 | 6 | # Specify which directories are to be excluded from coverage report 7 | coverage_ignore_dirs="\ 8 | '/usr/*' \ 9 | " 10 | 11 | # Run coverage for ins-node and ins-server 12 | eval mkdir -p $coverage_report_dir 13 | eval lcov --directory . --capture --output-file coverage.info 14 | eval lcov --remove coverage.info $coverage_ignore_dirs --output-file $coverage_report_dir/cpp_coverage.info 15 | eval lcov --list coverage.info 16 | 17 | # Go back to the initial directory when you are done 18 | cd $caller_dir -------------------------------------------------------------------------------- /src/battery.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "battery.h" 4 | #include "definitions.h" 5 | #include "configuration.h" 6 | #include "utils.h" 7 | 8 | Battery::Battery(IO_Analog& io_analog, TwoWire& w) : io_analog(io_analog), wire(w) {} 9 | 10 | void Battery::start() { 11 | 12 | // Set initial state. 13 | for (auto i = 0; i < CURRENT_MEDIAN_SAMPLES; i++) { 14 | updateChargeCurrent(); 15 | } 16 | 17 | updateBatteryVoltage(); 18 | Log.trace("Battery voltage: %F volt, charge current: %F mA" CR, batteryVoltage, lastChargeCurrentReading); 19 | 20 | // update battery voltage readings every XX second. 21 | batteryVoltageTicker.attach(BATTERY_VOLTAGE_DELAY, [](Battery* instance) { 22 | instance->updateBatteryVoltage(); 23 | }, this); 24 | // update battery charge current readings every XXX milliseconds. 25 | chargeCurrentTicker.attach_ms(BATTERY_CHARGECURRENT_DELAY, [](Battery* instance) { 26 | instance->updateChargeCurrent(); 27 | }, this); 28 | } 29 | 30 | void Battery::updateBatteryVoltage() { 31 | 32 | float adc_reading = io_analog.getVoltageAdc1(Definitions::BATTERY_SENSOR_CHANNEL); 33 | batteryVoltage = roundf((adc_reading * Definitions::BATTERY_MULTIPLIER) * 100) / 100; // adjust reading and round to two decimals. 34 | 35 | _needRecharge = batteryVoltage <= Definitions::BATTERY_EMPTY; 36 | _isFullyCharged = batteryVoltage >= Definitions::BATTERY_FULLY_CHARGED && !_isCharging; 37 | 38 | // make sure sample list don't grow larger than MAX_SAMPLES. Older samples are removed. 39 | if (batterySamples.size() >= MAX_SAMPLES) { 40 | batterySamples.pop_front(); 41 | } 42 | 43 | batterySamples.emplace_back(); 44 | auto& sample = batterySamples.back(); 45 | sample.time = Utils::getEpocTime(); 46 | sample.batteryVoltage = batteryVoltage; 47 | } 48 | 49 | void Battery::updateChargeCurrent() { 50 | 51 | auto chargeCurrent = 0;//ina219.getCurrent_mA(); TODO 52 | _isDocked = false;//ina219.getBusVoltage_V() > 5; TODO 53 | 54 | currentMedian[currentMedianIndex++ % CURRENT_MEDIAN_SAMPLES] = chargeCurrent; // enter new reading into array. 55 | // we can get some missreadings (1475.10) from time to time, so we record samples to an array an take the median value to filter out all noice. 56 | chargeCurrent = Utils::calculateMedian(currentMedian); 57 | 58 | _isCharging = chargeCurrent >= Definitions::CHARGE_CURRENT_THRESHOLD; 59 | // if we just started charging 60 | if (_isCharging && lastChargeCurrentReading < Definitions::CHARGE_CURRENT_THRESHOLD) { 61 | Log.notice("Start charging battery." CR); 62 | Log.trace("Charge current: %F mA" CR, chargeCurrent); 63 | 64 | // don't overwrite already existing starttime, we could have been charging with mower turned off. 65 | if (Configuration::config.startChargeTime == 0) { 66 | Configuration::config.startChargeTime = Utils::getEpocTime(); 67 | Configuration::save(); 68 | } 69 | } else if (!_isCharging && lastChargeCurrentReading >= Definitions::CHARGE_CURRENT_THRESHOLD) { 70 | 71 | if (_isFullyCharged) { 72 | Log.notice("Done charging battery." CR); 73 | auto currEpocSeconds = Utils::getEpocTime(); 74 | Configuration::config.lastFullyChargeTime = currEpocSeconds; 75 | if (Configuration::config.startChargeTime > 0) { 76 | Configuration::config.lastChargeDuration = currEpocSeconds - Configuration::config.startChargeTime; 77 | } 78 | } else { 79 | Log.notice("Charging of battery was aborted." CR); 80 | } 81 | // wipe starttime if charging was aborted or if we are done. 82 | Configuration::config.startChargeTime = 0; 83 | Configuration::save(); 84 | } 85 | 86 | lastChargeCurrentReading = chargeCurrent; 87 | } 88 | 89 | float Battery::getBatteryVoltage() const { 90 | return batteryVoltage; 91 | } 92 | 93 | float Battery::getChargeCurrent() const { 94 | // don't bother reporting stray-current when there is no charging going on. 95 | return lastChargeCurrentReading > 1.0 ? lastChargeCurrentReading : 0; 96 | } 97 | 98 | /* 99 | * Get battery status in percent, 100% = fully charged. 100 | */ 101 | uint8_t Battery::getBatteryStatus() const { 102 | 103 | auto level = round((batteryVoltage - Definitions::BATTERY_EMPTY) / (Definitions::BATTERY_FULLY_CHARGED - Definitions::BATTERY_EMPTY) * 100); 104 | if (level < 0) { 105 | level = 0; 106 | } else if (level > 100) { 107 | level = 100; 108 | } 109 | 110 | return level; 111 | } 112 | 113 | bool Battery::isDocked() const { 114 | return _isDocked; 115 | } 116 | 117 | bool Battery::isCharging() const { 118 | return _isCharging; 119 | } 120 | 121 | bool Battery::needRecharge() const { 122 | return _needRecharge; 123 | } 124 | 125 | bool Battery::isFullyCharged() const { 126 | return _isFullyCharged; 127 | } 128 | 129 | uint32_t Battery::getLastFullyChargeTime() const { 130 | return Configuration::config.lastFullyChargeTime; 131 | } 132 | 133 | uint32_t Battery::getLastChargeDuration() const { 134 | return Configuration::config.lastChargeDuration; 135 | } 136 | 137 | const std::deque& Battery::getBatteryHistory() const { 138 | return batterySamples; 139 | } 140 | -------------------------------------------------------------------------------- /src/battery.h: -------------------------------------------------------------------------------- 1 | #ifndef _battery_h 2 | #define _battery_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include "io_analog.h" 10 | 11 | struct batterySample { 12 | uint32_t time; 13 | float batteryVoltage; 14 | }; 15 | 16 | class Battery { 17 | public: 18 | Battery(IO_Analog& io_analog, TwoWire& w); 19 | float getBatteryVoltage() const; 20 | float getChargeCurrent() const; 21 | uint8_t getBatteryStatus() const; 22 | uint32_t getLastFullyChargeTime() const; 23 | uint32_t getLastChargeDuration() const; 24 | const std::deque& getBatteryHistory() const; 25 | bool isDocked() const; 26 | bool isCharging() const; 27 | bool needRecharge() const; 28 | bool isFullyCharged() const; 29 | void start(); 30 | 31 | private: 32 | static const uint16_t MAX_SAMPLES = 100; // How much history are we going to keep? set too high will consume excessive memory and we may get out-of-memory related errors. 33 | static const uint16_t BATTERY_CHARGECURRENT_DELAY = 100; // Read charge current every XXX milliseconds. 34 | static const uint16_t BATTERY_VOLTAGE_DELAY = 20; // Read battery voltage every XXX seconds. 35 | static const uint8_t CURRENT_MEDIAN_SAMPLES = 11; // How many samples should we take to calculate a median value for charge current. Don't fiddle with this unless needed. 36 | 37 | IO_Analog& io_analog; 38 | TwoWire& wire; 39 | float batteryVoltage = 0; 40 | float lastChargeCurrentReading = 0; 41 | bool _isDocked = false; 42 | bool _isCharging = false; 43 | bool _needRecharge = false; 44 | bool _isFullyCharged = false; 45 | float currentMedian[CURRENT_MEDIAN_SAMPLES] = {0}; 46 | uint8_t currentMedianIndex = 0; 47 | void updateBatteryVoltage(); 48 | void updateChargeCurrent(); 49 | Ticker batteryVoltageTicker; 50 | Ticker chargeCurrentTicker; 51 | std::deque batterySamples; 52 | }; 53 | 54 | #endif 55 | -------------------------------------------------------------------------------- /src/configuration.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "configuration.h" 4 | #include "log_store.h" 5 | #include "utils.h" 6 | 7 | namespace Configuration { 8 | 9 | Preferences preferences; 10 | configObject config; 11 | 12 | void load() { 13 | // this one is never saved/loaded from preferences, we just cache it here. 14 | // it's an unique id for every ESP32, also used as MAC-address for network. 15 | config.mowerId = Utils::uint64String(ESP.getEfuseMac()); 16 | 17 | preferences.begin("liam-esp", false); 18 | auto jsonString = preferences.getString("config", "{}"); 19 | DynamicJsonBuffer jsonBuffer(200); 20 | JsonObject& json = jsonBuffer.parseObject(jsonString); 21 | 22 | if (json.success()) { 23 | config.username = "admin"; 24 | if (json.containsKey("username")) { 25 | config.username = json["username"].as(); 26 | } 27 | 28 | config.password = "liam"; 29 | if (json.containsKey("password")) { 30 | config.password = json["password"].as(); 31 | } 32 | 33 | config.logLevel = LOG_LEVEL_NOTICE; 34 | if (json.containsKey("logLevel")) { 35 | config.logLevel = json["logLevel"]; 36 | } 37 | 38 | config.startChargeTime = json["startChargeTime"]; 39 | config.lastFullyChargeTime = json["lastFullyChargeTime"]; 40 | config.lastChargeDuration = json["lastChargeDuration"]; 41 | 42 | if (json.containsKey("lastState")) { 43 | config.lastState = json["lastState"].as(); 44 | } 45 | 46 | config.gmt = "0"; 47 | if (json.containsKey("gmt")) { 48 | config.gmt = json["gmt"].as(); 49 | } 50 | 51 | if (json.containsKey("wifiPassword")) { 52 | config.wifiPassword = json["wifiPassword"].as(); 53 | } 54 | 55 | if (json.containsKey("ssid")) { 56 | config.ssid = json["ssid"].as(); 57 | } 58 | 59 | if (json.containsKey("apiKey")) { 60 | config.apiKey = json["apiKey"].as(); 61 | } 62 | 63 | config.setupDone = false; 64 | if (json.containsKey("setupDone")) { 65 | config.setupDone = json["setupDone"]; 66 | } 67 | } 68 | 69 | Log.trace("Loaded settings from Flash: %s" CR, jsonString.c_str()); 70 | } 71 | 72 | void save() { 73 | DynamicJsonBuffer jsonBuffer(200); 74 | JsonObject& json = jsonBuffer.createObject(); 75 | 76 | json["username"] = config.username; 77 | json["password"] = config.password; 78 | json["logLevel"] = config.logLevel; 79 | json["startChargeTime"] = config.startChargeTime; 80 | json["lastFullyChargeTime"] = config.lastFullyChargeTime; 81 | json["lastChargeDuration"] = config.lastChargeDuration; 82 | json["lastState"] = config.lastState; 83 | json["gmt"] = config.gmt; 84 | json["wifiPassword"] = config.wifiPassword; 85 | json["ssid"] = config.ssid; 86 | json["apiKey"] = config.apiKey; 87 | json["setupDone"] = config.setupDone; 88 | 89 | String jsonString; 90 | json.printTo(jsonString); 91 | 92 | preferences.begin("liam-esp", false); 93 | preferences.putString("config", jsonString); 94 | 95 | Log.trace("Saved settings to Flash: %s" CR, jsonString.c_str()); 96 | } 97 | 98 | void wipe() { 99 | preferences.begin("liam-esp", false); 100 | preferences.clear(); 101 | } 102 | } 103 | -------------------------------------------------------------------------------- /src/configuration.h: -------------------------------------------------------------------------------- 1 | #ifndef _configuration_h 2 | #define _configuration_h 3 | 4 | #include 5 | #include 6 | 7 | /** 8 | * Class handling user configurable parameters of the application. It also takes care of storing and retereiving these from flash memory. 9 | */ 10 | namespace Configuration { 11 | 12 | struct configObject { 13 | String mowerId; 14 | String username; 15 | String password; 16 | int8_t logLevel; 17 | uint32_t startChargeTime = 0; 18 | uint32_t lastFullyChargeTime = 0; 19 | uint32_t lastChargeDuration = 0; 20 | String lastState; 21 | String gmt; 22 | String wifiPassword; 23 | String ssid; 24 | String apiKey; 25 | bool setupDone = false; 26 | }; 27 | 28 | extern Preferences preferences; 29 | extern configObject config; 30 | extern void load(); 31 | extern void save(); 32 | extern void wipe(); 33 | } 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /src/cutter.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "cutter.h" 3 | #include "definitions.h" 4 | #include "utils.h" 5 | 6 | Cutter::Cutter(IO_Analog& io_analog) : cutter_id(3), io_analog(io_analog) { 7 | pinMode(Definitions::CUTTER_MOTOR_PIN, OUTPUT); 8 | pinMode(Definitions::CUTTER_BRAKE_PIN, OUTPUT); 9 | digitalWrite(Definitions::CUTTER_BRAKE_PIN, LOW); 10 | 11 | ledcSetup(cutter_id, Definitions::MOTOR_BASE_FREQ, Definitions::MOTOR_TIMER_13_BIT); 12 | ledcAttachPin(Definitions::CUTTER_MOTOR_PIN, cutter_id); 13 | 14 | ledcWrite(cutter_id, cutterSpeed); 15 | } 16 | 17 | Cutter::~Cutter() { 18 | stop(true); 19 | } 20 | 21 | void Cutter::start() { 22 | if (cutterSpeed == 0) { 23 | cutterLoadReadingTicker.attach_ms(100, [](Cutter* instance) { 24 | instance->senseLoad(); 25 | }, this); 26 | 27 | digitalWrite(Definitions::CUTTER_BRAKE_PIN, LOW); 28 | 29 | delay(10); 30 | 31 | cutterSpeed = Definitions::CUTTER_MAX_SPEED; 32 | cutterCurrentSpeed = 1; 33 | 34 | setCutterSpeed(cutterCurrentSpeed); 35 | 36 | Log.trace(F("Cutter-start, speed: %d" CR), cutterSpeed); 37 | } 38 | } 39 | 40 | void Cutter::stop(bool brake) { 41 | if (cutterSpeed > 0) { 42 | cutterSpeed = 0; 43 | cutterCurrentSpeed = 0; 44 | 45 | setCutterSpeed(cutterCurrentSpeed); 46 | 47 | if (brake) { 48 | delay(10); 49 | digitalWrite(Definitions::CUTTER_BRAKE_PIN, HIGH); 50 | } else { 51 | digitalWrite(Definitions::CUTTER_BRAKE_PIN, LOW); 52 | } 53 | 54 | cutterLoadReadingTicker.detach(); 55 | load = 0; 56 | 57 | Log.trace(F("Cutter-stop, brake: %d" CR), brake); 58 | } 59 | } 60 | 61 | bool Cutter::isCutting() { 62 | return cutterSpeed > 0; 63 | } 64 | 65 | void Cutter::senseLoad() { 66 | 67 | auto current = round(io_analog.getVoltageAdc1(Definitions::CUTTER_LOAD_CHANNEL) / Definitions::CUTTER_LOAD_RESISTOR * 1000); // 1000 for converting ampere to milliampere 68 | auto newLoad = round((current - Definitions::CUTTER_NOLOAD_CURRENT) / (Definitions::CUTTER_MAX_CURRENT - Definitions::CUTTER_NOLOAD_CURRENT) * 100); 69 | 70 | // make sure we stay within percentage boundaries. 71 | if (newLoad < 0) { 72 | newLoad = 0; 73 | } else if (newLoad > 100) { 74 | newLoad = 100; 75 | } 76 | 77 | loadMedian[loadMedianIndex++ % LOAD_MEDIAN_SAMPLES] = newLoad; // enter new reading into array. 78 | load = Utils::calculateMedian(loadMedian); 79 | 80 | // keep count of how long we have been overloaded. This handles short burst of overload. 81 | if (load > Definitions::CUTTER_LOAD_THRESHOLD) { 82 | overloadCounter++; 83 | } else if (overloadCounter > 0) { 84 | overloadCounter--; 85 | } 86 | 87 | //Log.notice("%F mA, %d%%" CR, current, load); 88 | } 89 | 90 | void Cutter::setCutterSpeed(uint8_t speed) { 91 | 92 | if (speed == 0) { 93 | ledcWrite(cutter_id, 0); 94 | } else { 95 | // calculate duty, 8191 from 2 ^ 13 - 1 96 | uint32_t duty = ((pow(2, Definitions::MOTOR_TIMER_13_BIT) - 1) / 100) * abs(speed); 97 | ledcWrite(cutter_id, duty); 98 | } 99 | } 100 | 101 | uint8_t Cutter::getLoad() { 102 | return load; 103 | } 104 | 105 | /** 106 | * Signals that cuttermotor has surpassed the CUTTER_LOAD_THRESHOLD and is working too hard keeping up. 107 | * Continue working at this load may blow a fuse. 108 | */ 109 | bool Cutter::isOverloaded() { 110 | return overloadCounter > 15; 111 | } 112 | 113 | /** 114 | * Signals that the cuttermotor fuse has blown and we are no longer cutting any grass. 115 | * Stop cutter and wait a while for polyfuse to reset or replace fuse. 116 | */ 117 | bool Cutter::isFuseblown() { 118 | return isCutting() && load < 2; // are we cutting without any load? That is not possible unless motor is standing still. 119 | } 120 | 121 | void Cutter::process() { 122 | // slowly ramp cutter speed up to reach target ("cutterSpeed"), this is to save fuses and electronics from current surges. 123 | if (cutterCurrentSpeed < cutterSpeed) { 124 | 125 | if (millis() - cutterLastSpeedRamp > 50) { 126 | cutterLastSpeedRamp = millis(); 127 | cutterCurrentSpeed++; 128 | setCutterSpeed(cutterCurrentSpeed); 129 | } 130 | 131 | } else if (cutterCurrentSpeed > cutterSpeed) { 132 | 133 | cutterCurrentSpeed--; 134 | setCutterSpeed(cutterCurrentSpeed); 135 | 136 | } 137 | } -------------------------------------------------------------------------------- /src/cutter.h: -------------------------------------------------------------------------------- 1 | #ifndef _cutter_h 2 | #define _cutter_h 3 | 4 | #include 5 | #include 6 | #include "io_analog.h" 7 | #include "processable.h" 8 | 9 | 10 | /** 11 | * Class handling the cutter (the motor with knives) of the mower 12 | */ 13 | class Cutter : public Processable { 14 | public: 15 | Cutter(IO_Analog& io_analog); 16 | ~Cutter(); 17 | void start(); 18 | void stop(bool brake = true); 19 | bool isCutting(); 20 | uint8_t getLoad(); 21 | bool isOverloaded(); 22 | bool isFuseblown(); 23 | /* Internal use only! */ 24 | void process(); 25 | 26 | private: 27 | static const uint8_t LOAD_MEDIAN_SAMPLES = 5; // How many samples should we take to calculate a median value for cutter load. Don't fiddle with this unless needed. 28 | 29 | const uint8_t cutter_id; 30 | IO_Analog& io_analog; 31 | uint8_t cutterSpeed = 0; // target speed 32 | uint8_t cutterCurrentSpeed = 0; // current speed, when ramping up to cutterSpeed. 33 | long cutterLastSpeedRamp = 0; 34 | uint8_t load = 0; 35 | uint16_t overloadCounter = 0; 36 | uint8_t loadMedian[LOAD_MEDIAN_SAMPLES] = {0}; 37 | uint8_t loadMedianIndex = 0; 38 | Ticker cutterLoadReadingTicker; 39 | void senseLoad(); 40 | void setCutterSpeed(uint8_t speed); 41 | }; 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /src/definitions.h: -------------------------------------------------------------------------------- 1 | #ifndef _definitions_h 2 | #define _definitions_h 3 | 4 | #include 5 | 6 | namespace Definitions { 7 | 8 | /* 9 | Constants and other global stuff that you should probably never need to touch. 10 | */ 11 | extern const char* const APP_NAME; 12 | extern const char* const APP_VERSION; 13 | 14 | enum class MOWER_STATES { 15 | DOCKED, // mower is docked in its charging station and is fully charged 16 | LAUNCHING, // mower is leaving its charging station to head out for mowing 17 | MOWING, // mower is currently mowing 18 | DOCKING, // mower has stopped mowing and is heading back to its charging station (battery may be running low) 19 | CHARGING, // mower is docked in its charging station and is currently charging 20 | STUCK, // mower is stuck somewhere and have shutdown (it may be stuck in a hole, the cutter may be stuck, or some other hardware issue...) 21 | FLIPPED, // mower is flipped upside down or tiled too much, stopp mowing and wait to be unflipped. 22 | MANUAL, // mower is in manual drive mode and controlled by user from REST-API. 23 | STOP, // mower is stopped from it's normal operation, this happens when user press the physical stopbutton or UI button. 24 | TEST // mower is in test mode. 25 | }; 26 | 27 | extern const uint8_t SDA_PIN; 28 | extern const uint8_t SCL_PIN; 29 | 30 | extern const uint16_t DIGITAL_EXPANDER_ADDR; 31 | extern const uint16_t DIGITAL_EXPANDER_INTERRUPT_PIN; 32 | 33 | extern const uint16_t ADC1_ADDR; 34 | extern const uint16_t ADC2_ADDR; 35 | 36 | extern const float LORA_FREQ; 37 | extern const uint8_t LORA_DIO0_PIN; // interrupt pin #1 ("RxDone", "TxDone", "CadDone") 38 | extern const uint8_t LORA_DIO1_PIN; // interrupt pin #2 ("RxTimeout", "FhssChangeChannel", "CadDetected") 39 | 40 | extern const uint8_t MOTOR_TIMER_13_BIT; 41 | extern const uint16_t MOTOR_BASE_FREQ; 42 | extern const uint8_t LEFT_WHEEL_MOTOR_PIN; 43 | extern const uint8_t LEFT_WHEEL_MOTOR_DIRECTION_PIN; 44 | extern const uint8_t LEFT_WHEEL_MOTOR_LOAD_CHANNEL; 45 | extern const uint8_t LEFT_WHEEL_ODOMETER_PIN; 46 | extern const uint8_t LEFT_WHEEL_MOTOR_SPEED; 47 | extern const bool LEFT_WHEEL_MOTOR_INVERTED; 48 | extern const uint8_t RIGHT_WHEEL_MOTOR_PIN; 49 | extern const uint8_t RIGHT_WHEEL_MOTOR_DIRECTION_PIN; 50 | extern const uint8_t RIGHT_WHEEL_MOTOR_LOAD_CHANNEL; 51 | extern const uint8_t RIGHT_WHEEL_ODOMETER_PIN; 52 | extern const uint8_t RIGHT_WHEEL_MOTOR_SPEED; 53 | extern const bool RIGHT_WHEEL_MOTOR_INVERTED; 54 | extern const uint8_t WHEEL_MOTOR_MIN_SPEED; 55 | extern const uint8_t WHEEL_MOTOR_TURN_SPEED; 56 | extern const bool WHEEL_MOTOR_DECREASE_SPEED_AT_CUTTER_LOAD; 57 | extern const uint8_t LAUNCH_DISTANCE; 58 | extern const uint16_t WHEEL_ODOMETERPULSES_PER_ROTATION; 59 | extern const uint8_t WHEEL_DIAMETER; 60 | extern const uint8_t WHEEL_PAIR_DISTANCE; 61 | 62 | extern const uint8_t CUTTER_MOTOR_PIN; 63 | extern const uint8_t CUTTER_BRAKE_PIN; 64 | extern const uint8_t CUTTER_LOAD_CHANNEL; 65 | extern const float CUTTER_LOAD_RESISTOR; 66 | extern const float CUTTER_NOLOAD_CURRENT; 67 | extern const float CUTTER_MAX_CURRENT; 68 | extern const uint8_t CUTTER_MAX_SPEED; 69 | extern const uint16_t CUTTER_LOAD_THRESHOLD; 70 | 71 | extern const uint8_t EMERGENCY_STOP_PIN; 72 | 73 | extern const uint8_t DOCKED_DETECTION_PIN; 74 | extern const uint8_t BATTERY_SENSOR_CHANNEL; 75 | extern const float BATTERY_FULLY_CHARGED; 76 | extern const float BATTERY_EMPTY; 77 | extern const float BATTERY_MULTIPLIER; 78 | extern const float CHARGE_CURRENT_THRESHOLD; 79 | extern const float CHARGE_SHUNT_VALUE; 80 | 81 | extern const uint8_t TILT_ANGLE_MAX; 82 | 83 | extern const uint8_t FACTORY_RESET_PIN; 84 | 85 | extern const uint16_t MAX_LOGMESSAGES; 86 | 87 | extern const uint8_t SONAR_FRONT_PING_PIN; 88 | extern const uint8_t SONAR_FRONT_SENSE_PIN; 89 | extern const uint16_t SONAR_MAXDISTANCE; 90 | extern const uint16_t STUCK_RETRY_DELAY; 91 | 92 | extern const uint8_t MOWER_WIDTH; 93 | extern const uint8_t MOWER_LENGTH; 94 | extern const uint8_t CUTTER_DIAMETER; 95 | 96 | 97 | }; 98 | 99 | #endif 100 | -------------------------------------------------------------------------------- /src/dockingstation/dockingstation.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include "dockingstation.h" 5 | #include "esp_log.h" 6 | #include "definitions.h" 7 | #include "utils.h" 8 | #include "io_accelerometer/io_accelerometer.h" 9 | 10 | // Useful LoRa information: https://www.youtube.com/channel/UCG5_CT_KjexxjbgNE4lVGkg/videos 11 | 12 | /** 13 | * Class used for all communication with the docking station, over a low bandwidth, long range LoRa-connection. 14 | */ 15 | Dockingstation::Dockingstation(StateController& stateController, Resources& resources) : 16 | stateController(stateController), 17 | resources(resources), lora(new LoRa(SS, Definitions::LORA_DIO0_PIN, Definitions::LORA_DIO1_PIN)) { 18 | 19 | } 20 | 21 | /** 22 | * Collect status information from subsystems and push it to clients, if information has changed. 23 | */ 24 | void Dockingstation::collectAndPushNewStatus() { 25 | /*bool statusChanged = false; 26 | 27 | auto orient = resources.accelerometer.getOrientation(); 28 | auto wheelStats = resources.wheelController.getStatus(); 29 | auto obstacleDistances = resources.sonar.getObstacleDistances(); 30 | 31 | currentStatus.state = stateController.getStateInstance()->getStateName(); 32 | currentStatus.batteryVoltage = resources.battery.getBatteryVoltage(); 33 | currentStatus.batteryLevel = resources.battery.getBatteryStatus(); 34 | currentStatus.batteryChargeCurrent = resources.battery.getChargeCurrent(); 35 | currentStatus.isCharging = resources.battery.isCharging(); 36 | currentStatus.lastFullyChargeTime = resources.battery.getLastFullyChargeTime(); 37 | currentStatus.lastChargeDuration = resources.battery.getLastChargeDuration(); 38 | currentStatus.cutterLoad = resources.cutter.getLoad(); 39 | currentStatus.cutterRotating = resources.cutter.isCutting(); 40 | currentStatus.leftWheelSpd = wheelStats.leftWheelSpeed; 41 | currentStatus.rightWheelSpd = wheelStats.rightWheelSpeed; 42 | currentStatus.obstacleLeftDistance = obstacleDistances.leftDistance; 43 | currentStatus.obstacleFrontDistance = obstacleDistances.frontDistance; 44 | currentStatus.obstacleRightDistance = obstacleDistances.rightDistance; 45 | currentStatus.pitch = orient.pitch; 46 | currentStatus.roll = orient.roll; 47 | currentStatus.heading = orient.heading; 48 | 49 | if (currentStatus.state != stateController.getStateInstance()->getStateName() || 50 | currentStatus.batteryVoltage != resources.battery.getBatteryVoltage() || 51 | currentStatus.batteryLevel != resources.battery.getBatteryStatus() || 52 | currentStatus.batteryChargeCurrent != resources.battery.getChargeCurrent() || 53 | currentStatus.isCharging != resources.battery.isCharging() || 54 | currentStatus.lastFullyChargeTime != resources.battery.getLastFullyChargeTime() || 55 | currentStatus.lastChargeDuration != resources.battery.getLastChargeDuration() || 56 | currentStatus.cutterLoad != resources.cutter.getLoad() || 57 | currentStatus.cutterRotating != resources.cutter.isCutting() || 58 | currentStatus.leftWheelSpd != wheelStats.leftWheelSpeed || 59 | currentStatus.rightWheelSpd != wheelStats.rightWheelSpeed || 60 | currentStatus.obstacleLeftDistance != obstacleDistances.leftDistance || 61 | currentStatus.obstacleFrontDistance != obstacleDistances.frontDistance || 62 | currentStatus.obstacleRightDistance != obstacleDistances.rightDistance || 63 | currentStatus.pitch != orient.pitch || 64 | currentStatus.roll != orient.roll || 65 | currentStatus.heading != orient.heading 66 | ) { 67 | statusChanged = true; 68 | } 69 | 70 | // we have to check that we are connected before we try to get WiFi signal, otherwise it will freeze up. 71 | if (WiFi.status() == WL_CONNECTED) { 72 | auto wifiSignal = WiFi.RSSI(); 73 | 74 | if (currentStatus.wifiSignal != wifiSignal) { 75 | currentStatus.wifiSignal = wifiSignal; 76 | statusChanged = true; 77 | } 78 | } 79 | 80 | // These change so often that we don't set statusChanged for these, otherwise we would push everytime. 81 | currentStatus.uptime = (uint32_t)(esp_timer_get_time() / 1000000); // uptime in microseconds so we divide to seconds. 82 | 83 | if (statusChanged) { 84 | DynamicJsonBuffer jsonBuffer(380); 85 | JsonObject& root = jsonBuffer.createObject(); 86 | statusToJson(currentStatus, root); 87 | 88 | resources.wlan.sendDataWebSocket("status", root); 89 | 90 | // MQTT updates don't have to be "realtime", we can settle with an update every 10 sec to not spam server. 91 | if (lastMQTT_push < currentStatus.uptime - 10) { 92 | String jsonStr; 93 | root.printTo(jsonStr); 94 | resources.wlan.publish_mqtt(jsonStr.c_str(), "/status"); 95 | lastMQTT_push = currentStatus.uptime; 96 | } 97 | }*/ 98 | } 99 | 100 | void Dockingstation::start() { 101 | // carrier frequency: MHz 102 | // bandwidth: 250.0 kHz 103 | // spreading factor: 7 104 | // coding rate: 4 105 | // sync word: 0x12 106 | // output power: 2 dBm 107 | // current limit: 50 mA 108 | // preamble length: 8 symbols 109 | // amplifier gain: 1 (maximum gain) 110 | int state = lora.begin(Definitions::LORA_FREQ, 250, 7, 4, 0x12, 2, 50, 8, 1); 111 | if (state == ERR_NONE) { 112 | Log.notice(F("LoRa success!" CR)); 113 | } else { 114 | Log.notice(F("LoRa failed, code %d" CR), state); 115 | } 116 | 117 | 118 | // start scanning current channel 119 | int scanresult = lora.scanChannel(); 120 | 121 | if(scanresult == PREAMBLE_DETECTED) { 122 | // LoRa preamble was detected 123 | Log.notice(F(" detected preamble!" CR)); 124 | 125 | } else if(scanresult == CHANNEL_FREE) { 126 | // no preamble was detected, channel is free 127 | Log.notice(F(" channel is free!" CR)); 128 | 129 | } 130 | 131 | //https://github.com/sandeepmistry/arduino-LoRa/blob/master/examples/LoRaDuplex/LoRaDuplex.ino 132 | //https://github.com/sandeepmistry/arduino-LoRa/blob/master/examples/LoRaDuplexCallback/LoRaDuplexCallback.ino 133 | } 134 | 135 | -------------------------------------------------------------------------------- /src/dockingstation/dockingstation.h: -------------------------------------------------------------------------------- 1 | #ifndef _liam_dockingstation_h 2 | #define _liam_dockingstation_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "state_controller.h" 8 | #include "resources.h" 9 | 10 | class Dockingstation { 11 | public: 12 | Dockingstation(StateController& stateController, Resources& resources); 13 | void start(); 14 | 15 | private: 16 | StateController& stateController; 17 | Resources& resources; 18 | Ticker pushNewInfoTicker; 19 | SX1278 lora; 20 | void collectAndPushNewStatus(); 21 | }; 22 | 23 | #endif 24 | -------------------------------------------------------------------------------- /src/dockingstation/sign_on.proto: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/src/dockingstation/sign_on.proto -------------------------------------------------------------------------------- /src/dockingstation/sign_on_resp.proto: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/src/dockingstation/sign_on_resp.proto -------------------------------------------------------------------------------- /src/dockingstation/status.proto: -------------------------------------------------------------------------------- 1 | syntax = "proto3"; 2 | 3 | message Status { 4 | required uint8 state = 1; 5 | required double batteryVoltage = 2; 6 | required uint8 batteryLevel = 3; 7 | } 8 | json["state"] = obj.state; 9 | json["batteryVoltage"] = obj.batteryVoltage; 10 | json["batteryLevel"] = obj.batteryLevel; 11 | json["batteryChargeCurrent"] = obj.batteryChargeCurrent; 12 | json["isCharging"] = obj.isCharging; 13 | json["lastFullyChargeTime"] = obj.lastFullyChargeTime; 14 | json["lastChargeDuration"] = obj.lastChargeDuration; 15 | json["cutterLoad"] = obj.cutterLoad; 16 | json["cutterRotating"] = obj.cutterRotating; 17 | json["uptime"] = obj.uptime; 18 | json["wifiSignal"] = obj.wifiSignal; 19 | json["leftWheelSpd"] = obj.leftWheelSpd; 20 | json["rightWheelSpd"] = obj.rightWheelSpd; 21 | json["pitch"] = obj.pitch; 22 | json["roll"] = obj.roll; 23 | json["heading"] = obj.heading; 24 | JsonObject& obstacles = json.createNestedObject("obstacles"); 25 | obstacles["left"] = obj.obstacleLeftDistance; 26 | obstacles["front"] = obj.obstacleFrontDistance; 27 | obstacles["right"] = obj.obstacleRightDistance; -------------------------------------------------------------------------------- /src/dockingstation/system.proto: -------------------------------------------------------------------------------- 1 | 2 | root["name"] = Definitions::APP_NAME; 3 | root["version"] = Definitions::APP_VERSION; 4 | root["mowerId"] = Configuration::config.mowerId; 5 | root["totalHeap"] = ESP.getHeapSize(); // total heap size 6 | root["freeHeap"] = ESP.getFreeHeap(); // available heap 7 | root["minFreeHeap"] = ESP.getMinFreeHeap(); // lowest level of free heap we had since boot 8 | root["getMaxAllocHeap"] = ESP.getMaxAllocHeap(); // largest block of heap that can be allocated at once (heap is usually fragmented, a large value indicated low fragmentation which is good) 9 | root["apiKey"] = Configuration::config.apiKey; 10 | root["localTime"] = Utils::getTime(); 11 | JsonObject& settings = root.createNestedObject("settings"); 12 | settings["batteryFullVoltage"] = Definitions::BATTERY_FULLY_CHARGED; 13 | settings["batteryEmptyVoltage"] = Definitions::BATTERY_EMPTY; -------------------------------------------------------------------------------- /src/gps.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "gps.h" 3 | #include "definitions.h" 4 | 5 | // RTK baserad GPS. Här finns karta över närliggande stationer: http://www.epncb.oma.be/_networkdata/data_access/real_time/map.php 6 | // u-blox NEO-7N, ±6-10 meter 7 | // u-blox NEO-8T, ±1-6 meter 8 | // u-blox ZED-F9P, ±1 meter without RTCM, 1-2 centimeter when using RTCM signal. 9 | // 10 | // Information about RTK: https://gssc.esa.int/navipedia/index.php/Real_Time_Kinematics and //https://www.youtube.com/watch?v=n8PUyOtiGKo 11 | // Useful RTK blog: http://rtkexplorer.com 12 | 13 | //https://github.com/Ultimaker/CuraEngine/blob/master/src/slicer.h 14 | //https://github.com/Ultimaker/CuraEngine/blob/master/src/slicer.cpp 15 | //https://github.com/Ultimaker/CuraEngine/blob/master/src/infill.cpp 16 | 17 | GPS::GPS() {} 18 | 19 | void GPS::init() 20 | { 21 | if (gps.begin() == false) //Connect to the Ublox module using Wire port 22 | { 23 | Log.warning(F("Ublox GPS not detected at default I2C address. Please check wiring, and restart mower!")); 24 | while (1) 25 | ; 26 | } 27 | 28 | Serial.print(F("Version: ")); 29 | byte versionHigh = gps.getProtocolVersionHigh(); 30 | Serial.print(versionHigh); 31 | Serial.print("."); 32 | byte versionLow = gps.getProtocolVersionLow(); 33 | Serial.print(versionLow); 34 | 35 | gps.setI2COutput(COM_TYPE_UBX); // Set the I2C port to output UBX only (turn off NMEA noise) 36 | gps.setNavigationFrequency(10); // Set output to 10 times a second 37 | gps.setAutoPVT(true); // Don't block for updates, library will internally serve the latest readings is has instead of waiting for new ones to finish. 38 | gps.saveConfiguration(); // Save the current settings to flash and battery backed RAM 39 | 40 | byte rate = gps.getNavigationFrequency(); 41 | Serial.print("Current update rate:"); 42 | Serial.println(rate); 43 | } 44 | 45 | void GPS::start() 46 | { 47 | // TODO: remove this code when done debugging, not needed since setAutoPVT(true)! 48 | if (millis() - lastTime > 1000) 49 | { 50 | lastTime = millis(); //Update the timer 51 | 52 | /* Note: Long/lat are large numbers because they are * 10^9. To convert lat/long 53 | to something google maps understands simply divide the numbers by 100,000,000. We 54 | do this so that we don't have to use floating point numbers. */ 55 | int32_t latitude = gps.getHighResLatitude(); 56 | Serial.print(F("Lat: ")); 57 | Serial.print(latitude); 58 | 59 | int32_t longitude = gps.getHighResLongitude(); 60 | Serial.print(F(" Long: ")); 61 | Serial.print(longitude); 62 | 63 | int32_t altitude = gps.getAltitude(); 64 | Serial.print(F(" Alt: ")); 65 | Serial.print(altitude); 66 | 67 | int32_t speed = gps.getGroundSpeed(); 68 | Serial.print(F(" Speed: ")); 69 | Serial.print(speed); 70 | Serial.print(F(" (mm/s)")); 71 | 72 | int32_t heading = gps.getHeading(); 73 | Serial.print(F(" Heading: ")); 74 | Serial.print(heading); 75 | Serial.print(F(" (degrees * 10^-5)")); 76 | 77 | int pDOP = gps.getPDOP(); 78 | Serial.print(F(" pDOP: ")); 79 | Serial.print(pDOP / 100.0, 2); 80 | 81 | byte fixType = gps.getFixType(); 82 | Serial.print(F(" Fix: ")); 83 | if (fixType == 0) 84 | Serial.print(F("No fix")); 85 | else if (fixType == 1) 86 | Serial.print(F("Dead reckoning")); 87 | else if (fixType == 2) 88 | Serial.print(F("2D")); 89 | else if (fixType == 3) 90 | Serial.print(F("3D")); 91 | else if (fixType == 4) 92 | Serial.print(F("GNSS+Dead reckoning")); 93 | 94 | byte RTK = gps.getCarrierSolutionType(); 95 | Serial.print(" RTK: "); 96 | Serial.print(RTK); 97 | if (RTK == 1) 98 | Serial.print(F("High precision float fix!")); 99 | if (RTK == 2) 100 | Serial.print(F("High precision fix!")); 101 | Serial.println(); 102 | 103 | int32_t accuracy = gps.getPositionAccuracy(); 104 | Serial.print(F(" 3D Positional Accuracy: ")); 105 | Serial.print(accuracy); 106 | Serial.println(F("mm")); 107 | 108 | uint32_t horizontalAccuracy = gps.getHorizontalAccuracy(); 109 | Serial.print(F(" Horizontal accuracy: ")); 110 | Serial.print(horizontalAccuracy); 111 | Serial.println(F("mm")); 112 | 113 | // https://github.com/sparkfun/SparkFun_Ublox_Arduino_Library/blob/master/examples/Example13_PVT/Example1_AutoPVT/Example1_AutoPVT.ino 114 | // https://github.com/sparkfun/SparkFun_Ublox_Arduino_Library/commit/63fb62ebd12c46c062d059c0fabe309f2d280098 115 | } 116 | } 117 | 118 | const std::deque &GPS::getGpsPositionHistory() const 119 | { 120 | return gpsPosistionSamples; 121 | } 122 | -------------------------------------------------------------------------------- /src/gps.h: -------------------------------------------------------------------------------- 1 | #ifndef _gps_h 2 | #define _gps_h 3 | 4 | #include 5 | #include "SparkFun_Ublox_Arduino_Library.h" 6 | #include 7 | 8 | struct gpsPosition { 9 | uint32_t time; 10 | long lat; 11 | long lng; 12 | }; 13 | 14 | class GPS { 15 | public: 16 | GPS(); 17 | void init(); 18 | void start(); 19 | const std::deque& getGpsPositionHistory() const; 20 | private: 21 | static const uint16_t MAX_SAMPLES = 100; // How much history are we going to keep? set too high will consume excessive memory and we may get out-of-memory related errors. 22 | SFE_UBLOX_GPS gps; 23 | long lastTime = 0; //Simple local timer. TODO: remove this when done debugging. 24 | std::deque gpsPosistionSamples; 25 | gpsPosition lastMowingPosition; 26 | }; 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /src/io_accelerometer/io_accelerometer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include "definitions.h" 5 | #include "io_accelerometer.h" 6 | #include "utils.h" 7 | 8 | // https://github.com/sparkfun/ESP32_Motion_Shield/tree/master/Software 9 | // https://learn.sparkfun.com/tutorials/esp32-thing-motion-shield-hookup-guide/using-the-imu 10 | 11 | IO_Accelerometer::IO_Accelerometer(TwoWire& w): _Wire(w) { 12 | 13 | // the device's communication mode and addresses: 14 | imu.settings.device.commInterface = IMU_MODE_I2C; 15 | //imu.settings.device.mAddress = LSM9DS1_M; 16 | //imu.settings.device.agAddress = LSM9DS1_AG; 17 | } 18 | 19 | void IO_Accelerometer::start() { 20 | 21 | if (!imu.begin()) { 22 | Log.error(F("Failed to initialize gyro/accelerometer/compass, check connections!")); 23 | } else { 24 | Log.notice(F("Gyro/accelerometer/compass init success." CR)); 25 | available = true; 26 | 27 | imu.calibrate(true); 28 | //imu.calibrateMag(true); //TODO: check why this crashes with: Guru Meditation Error: Core 1 panic'ed (StoreProhibited). Exception was unhandled. 29 | 30 | sensorReadingTicker.attach_ms(20, [](IO_Accelerometer* instance) { 31 | instance->getReadings(); 32 | }, this); 33 | } 34 | } 35 | 36 | bool IO_Accelerometer::isAvailable() const { 37 | return available; 38 | } 39 | 40 | const Orientation& IO_Accelerometer::getOrientation() const { 41 | return currentOrientation; 42 | } 43 | 44 | bool IO_Accelerometer::isFlipped() const { 45 | if (available == false) { 46 | return false; 47 | } else { 48 | return (abs(currentOrientation.pitch) > Definitions::TILT_ANGLE_MAX || abs(currentOrientation.roll) > Definitions::TILT_ANGLE_MAX); 49 | } 50 | } 51 | 52 | void IO_Accelerometer::getReadings() { 53 | 54 | if (available) { 55 | // Update the sensor values whenever new data is available 56 | if ( imu.accelAvailable() ) { 57 | // To read from the accelerometer, first call the 58 | // readAccel() function. When it exits, it'll update the 59 | // ax, ay, and az variables with the most current data. 60 | imu.readAccel(); 61 | ax = imu.calcAccel(imu.ax); 62 | ay = imu.calcAccel(imu.ay); 63 | az = imu.calcAccel(imu.az); 64 | } 65 | if ( imu.gyroAvailable() ) { 66 | // To read from the gyroscope, first call the 67 | // readGyro() function. When it exits, it'll update the 68 | // gx, gy, and gz variables with the most current data. 69 | imu.readGyro(); 70 | gx = imu.calcGyro(imu.gx) * PI / 180.0f; // convert from radians to degrees 71 | gy = imu.calcGyro(imu.gy) * PI / 180.0f; 72 | gz = imu.calcGyro(imu.gz) * PI / 180.0f; 73 | } 74 | if ( imu.magAvailable() ) { 75 | // To read from the magnetometer, first call the 76 | // readMag() function. When it exits, it'll update the 77 | // mx, my, and mz variables with the most current data. 78 | imu.readMag(); 79 | mx = imu.calcMag(imu.mx); 80 | my = imu.calcMag(imu.my); 81 | mz = imu.calcMag(imu.mz); 82 | } 83 | 84 | for (uint8_t i = 0; i < 10; i++) { // iterate a fixed number of times per data read cycle 85 | now = micros(); 86 | 87 | deltaTime = (now - lastUpdate) / 1000000.0f; // set integration time by time elapsed since last filter update 88 | lastUpdate = now; 89 | 90 | filter.madgwickQuaternionUpdate(deltaTime, -ax, +ay, +az, gx, -gy, -gz, my, -mx, mz); 91 | } 92 | 93 | auto quaternion = filter.getQuaternions(); 94 | 95 | auto a12 = 2.0f * (quaternion.q2 * quaternion.q3 + quaternion.q1 * quaternion.q4); 96 | auto a22 = quaternion.q1 * quaternion.q1 + quaternion.q2 * quaternion.q2 - quaternion.q3 * quaternion.q3 - quaternion.q4 * quaternion.q4; 97 | auto a31 = 2.0f * (quaternion.q1 * quaternion.q2 + quaternion.q3 * quaternion.q4); 98 | auto a32 = 2.0f * (quaternion.q2 * quaternion.q4 - quaternion.q1 * quaternion.q3); 99 | auto a33 = quaternion.q1 * quaternion.q1 - quaternion.q2 * quaternion.q2 - quaternion.q3 * quaternion.q3 + quaternion.q4 * quaternion.q4; 100 | auto pitch = -asinf(a32); 101 | auto roll = atan2f(a31, a33); 102 | auto yaw = atan2f(a12, a22); 103 | 104 | // Convert everything from radians to degrees: 105 | pitch *= 180.0f / PI; 106 | roll *= 180.0f / PI; 107 | yaw *= 180.0f / PI; 108 | 109 | yaw -= DECLINATION; 110 | 111 | if (yaw < 0) { 112 | yaw += 360.0f; // Ensure yaw stays between 0 and 360 113 | } 114 | 115 | // acceleration without gravity involved, could be used to detect when we bump into obstacles. 116 | //auto lin_ax1 = ax + a31; 117 | //auto lin_ay1 = ay + a32; 118 | //auto lin_az1 = az - a33; 119 | 120 | currentOrientation.roll = roundf(roll); 121 | currentOrientation.pitch = roundf(pitch); 122 | currentOrientation.heading = roundf(yaw); 123 | 124 | //Log.notice("Roll: %d, Pitch: %d, Heading: %d" CR, currentOrientation.roll, currentOrientation.pitch, currentOrientation.heading); 125 | } 126 | } 127 | -------------------------------------------------------------------------------- /src/io_accelerometer/io_accelerometer.h: -------------------------------------------------------------------------------- 1 | #ifndef accelerometer_h 2 | #define accelerometer_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "madgwick_filters.h" 8 | 9 | struct Orientation { 10 | int16_t pitch = 0; 11 | int16_t roll = 0; 12 | uint16_t heading = 0; 13 | }; 14 | 15 | class IO_Accelerometer { 16 | public: 17 | IO_Accelerometer(TwoWire& w); 18 | bool isAvailable() const; 19 | bool isFlipped() const; 20 | const Orientation& getOrientation() const; 21 | void start(); 22 | 23 | private: 24 | // Earth's magnetic field varies by location. Add or subtract 25 | // a declination to get a more accurate heading of true magnetic north. 26 | // Use an compass for reference. 27 | float DECLINATION = -50.0f; // Declination (degrees) in Gotland, SE. 28 | 29 | 30 | LSM9DS1 imu; 31 | TwoWire& _Wire; 32 | Ticker sensorReadingTicker; 33 | Orientation currentOrientation; 34 | MadgwickFilters filter; 35 | 36 | bool available = false; 37 | unsigned long lastUpdate = 0; 38 | unsigned long now = 0; 39 | float deltaTime = 0.0f; 40 | float ax = 0.0f; 41 | float ay = 0.0f; 42 | float az = 0.0f; 43 | float gx = 0.0f; 44 | float gy = 0.0f; 45 | float gz = 0.0f; 46 | float mx = 0.0f; 47 | float my = 0.0f; 48 | float mz = 0.0f; 49 | void getReadings(); 50 | }; 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /src/io_accelerometer/madgwick_filters.cpp: -------------------------------------------------------------------------------- 1 | // Borrowed from Kris Winers https://github.com/kriswiner/MPU6050HMC5883AHRS/blob/master/quaternion%20Filters.ino 2 | // also read https://github.com/kriswiner/MPU6050/wiki/Affordable-9-DoF-Sensor-Fusion 3 | 4 | // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 5 | // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 6 | // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 7 | // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 8 | // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 9 | // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 10 | 11 | #include "madgwick_filters.h" 12 | 13 | MadgwickFilters::MadgwickFilters() { 14 | 15 | } 16 | 17 | /** 18 | * Fuses sensors readings using Madgwick filter 19 | * @param ax accleration value in g's 20 | * @param ay accleration value in g's 21 | * @param az accleration value in g's 22 | * @param gx gyro value into actual degrees per second 23 | * @param gy gyro value into actual degrees per second 24 | * @param gz gyro value into actual degrees per second 25 | * @param mx magnetometer values in milliGauss 26 | * @param my magnetometer values in milliGauss 27 | * @param mz magnetometer values in milliGauss 28 | */ 29 | __attribute__((optimize("O3"))) void MadgwickFilters::madgwickQuaternionUpdate(float deltaTime, float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) { 30 | 31 | float q1 = quaternion.q1, q2 = quaternion.q2, q3 = quaternion.q3, q4 = quaternion.q4; // short name local variable for readability 32 | float norm; 33 | float hx, hy, _2bx, _2bz; 34 | float s1, s2, s3, s4; 35 | float qDot1, qDot2, qDot3, qDot4; 36 | 37 | // Auxiliary variables to avoid repeated arithmetic 38 | float _2q1mx; 39 | float _2q1my; 40 | float _2q1mz; 41 | float _2q2mx; 42 | float _4bx; 43 | float _4bz; 44 | float _2q1 = 2.0f * q1; 45 | float _2q2 = 2.0f * q2; 46 | float _2q3 = 2.0f * q3; 47 | float _2q4 = 2.0f * q4; 48 | float _2q1q3 = 2.0f * q1 * q3; 49 | float _2q3q4 = 2.0f * q3 * q4; 50 | float q1q1 = q1 * q1; 51 | float q1q2 = q1 * q2; 52 | float q1q3 = q1 * q3; 53 | float q1q4 = q1 * q4; 54 | float q2q2 = q2 * q2; 55 | float q2q3 = q2 * q3; 56 | float q2q4 = q2 * q4; 57 | float q3q3 = q3 * q3; 58 | float q3q4 = q3 * q4; 59 | float q4q4 = q4 * q4; 60 | 61 | // Normalise accelerometer measurement 62 | norm = sqrtf(ax * ax + ay * ay + az * az); 63 | if (norm == 0.0f) return; // handle NaN 64 | norm = 1.0f/norm; 65 | ax *= norm; 66 | ay *= norm; 67 | az *= norm; 68 | 69 | // Normalise magnetometer measurement 70 | norm = sqrtf(mx * mx + my * my + mz * mz); 71 | if (norm == 0.0f) return; // handle NaN 72 | norm = 1.0f/norm; 73 | mx *= norm; 74 | my *= norm; 75 | mz *= norm; 76 | 77 | // Reference direction of Earth's magnetic field 78 | _2q1mx = 2.0f * q1 * mx; 79 | _2q1my = 2.0f * q1 * my; 80 | _2q1mz = 2.0f * q1 * mz; 81 | _2q2mx = 2.0f * q2 * mx; 82 | hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; 83 | hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; 84 | _2bx = sqrtf(hx * hx + hy * hy); 85 | _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; 86 | _4bx = 2.0f * _2bx; 87 | _4bz = 2.0f * _2bz; 88 | 89 | // Gradient decent algorithm corrective step 90 | s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 91 | s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 92 | s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 93 | s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 94 | norm = sqrtf(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude 95 | norm = 1.0f/norm; 96 | s1 *= norm; 97 | s2 *= norm; 98 | s3 *= norm; 99 | s4 *= norm; 100 | 101 | // Compute rate of change of quaternion 102 | qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; 103 | qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; 104 | qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; 105 | qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; 106 | 107 | // Integrate to yield quaternion 108 | q1 += qDot1 * deltaTime; 109 | q2 += qDot2 * deltaTime; 110 | q3 += qDot3 * deltaTime; 111 | q4 += qDot4 * deltaTime; 112 | norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 113 | norm = 1.0f/norm; 114 | quaternion.q1 = q1 * norm; 115 | quaternion.q2 = q2 * norm; 116 | quaternion.q3 = q3 * norm; 117 | quaternion.q4 = q4 * norm; 118 | 119 | } 120 | 121 | const Quaternion& MadgwickFilters::getQuaternions() const { 122 | return quaternion; 123 | } 124 | -------------------------------------------------------------------------------- /src/io_accelerometer/madgwick_filters.h: -------------------------------------------------------------------------------- 1 | // Borrowed from Kris Winers https://github.com/kriswiner/MPU9250/blob/master/Dual_MPU9250/MadgwickFilters 2 | 3 | // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 4 | // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 5 | // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 6 | // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 7 | // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 8 | // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 9 | #ifndef madgwick_filters_h 10 | #define madgwick_filters_h 11 | 12 | #include 13 | 14 | struct Quaternion { 15 | float q1 = 1.0f; 16 | float q2 = 0.0f; 17 | float q3 = 0.0f; 18 | float q4 = 0.0f; 19 | }; 20 | 21 | class MadgwickFilters { 22 | private: 23 | float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) 24 | float beta = sqrtf(3.0f / 4.0f) * GyroMeasError; // compute beta 25 | Quaternion quaternion; 26 | 27 | 28 | public: 29 | MadgwickFilters(); 30 | __attribute__((optimize("O3"))) void madgwickQuaternionUpdate(float deltaTime, float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz); 31 | const Quaternion& getQuaternions() const; 32 | }; 33 | 34 | #endif -------------------------------------------------------------------------------- /src/io_analog.cpp: -------------------------------------------------------------------------------- 1 | #include "io_analog.h" 2 | 3 | // Shunt sizing: 4 | // https://www.spiria.com/en/blog/iot-m2m-embedded-solutions/measuring-small-currents-adc 5 | 6 | // http://henrysbench.capnfatz.com/henrys-bench/arduino-voltage-measurements/arduino-ads1115-module-getting-started-tutorial/ 7 | // https://learn.adafruit.com/adafruit-4-channel-adc-breakouts/arduino-code 8 | 9 | IO_Analog::IO_Analog() : adc1(Definitions::ADC1_ADDR), adc2(Definitions::ADC2_ADDR) { 10 | 11 | // The ADC input range (or gain) can be changed via the following 12 | // functions, but be careful never to exceed VDD +0.3V max, or to 13 | // exceed the upper and lower limits if you adjust the input range! 14 | // Setting these values incorrectly may destroy your ADC! 15 | // ADS1015 ADS1115 16 | // ------- ------- 17 | // adc.setGain(GAIN_TWOTHIRDS); // 2/3x gain +/- 6.144V 1 bit = 3mV 0.1875mV (default) 18 | // adc.setGain(GAIN_ONE); // 1x gain +/- 4.096V 1 bit = 2mV 0.125mV 19 | adc1.setGain(GAIN_TWO); // 2x gain +/- 2.048V 1 bit = 1mV 0.0625mV 20 | // adc.setGain(GAIN_FOUR); // 4x gain +/- 1.024V 1 bit = 0.5mV 0.03125mV 21 | // adc.setGain(GAIN_EIGHT); // 8x gain +/- 0.512V 1 bit = 0.25mV 0.015625mV 22 | // adc.setGain(GAIN_SIXTEEN); // 16x gain +/- 0.256V 1 bit = 0.125mV 0.0078125mV 23 | 24 | adc2.setGain(GAIN_TWO); // 2x gain +/- 2.048V 1 bit = 1mV 0.0625mV 25 | adc2.startContinuous_Differential_0_1(); // Hardwired for monitoring charge current. 26 | } 27 | 28 | float IO_Analog::getVoltageAdc1(uint8_t channel) { 29 | 30 | return adc1.readADC_SingleEnded_V(channel); 31 | 32 | } 33 | 34 | float IO_Analog::getChargeCurrent() { 35 | 36 | return ((float) adc2.getLastConversionResults()) * adc2.voltsPerBit() / Definitions::CHARGE_SHUNT_VALUE; 37 | 38 | } 39 | -------------------------------------------------------------------------------- /src/io_analog.h: -------------------------------------------------------------------------------- 1 | #ifndef io_analog_h 2 | #define io_analog_h 3 | 4 | #include 5 | #include 6 | #include "definitions.h" 7 | 8 | 9 | /** 10 | * Analog to Digital converter, used to read battery voltage, charge voltage, cutter motor load, and more. 11 | */ 12 | class IO_Analog { 13 | public: 14 | IO_Analog(); 15 | 16 | /** 17 | * Get the voltage readings from the specified channel of ADC #1. 18 | */ 19 | float getVoltageAdc1(uint8_t channel); 20 | float getChargeCurrent(); 21 | 22 | private: 23 | Adafruit_ADS1115 adc1; 24 | Adafruit_ADS1115 adc2; 25 | }; 26 | 27 | #endif 28 | -------------------------------------------------------------------------------- /src/io_digital.cpp: -------------------------------------------------------------------------------- 1 | #include "Arduino.h" 2 | #include "io_digital.h" 3 | #include "definitions.h" 4 | 5 | // Useful MCP23017 information: https://www.best-microcontroller-projects.com/mcp23017.html 6 | 7 | IO_Digital::IO_Digital(TwoWire& w): _Wire(w), device(Definitions::DIGITAL_EXPANDER_ADDR, w) { 8 | 9 | device.init(); 10 | device.interruptMode(MCP23017_INTMODE::OR); 11 | 12 | } 13 | 14 | void IO_Digital::setPinMode(uint8_t pin, bool input) { 15 | device.pinMode(pin, input); 16 | } 17 | 18 | void IO_Digital::digitalWrite(uint8_t pin, bool state) { 19 | /* 20 | https://github.com/blemasle/arduino-mcp23017/blob/master/examples/PortCopyOnInterrupt/PortCopyOnInterrupt.ino 21 | mcp.init(); 22 | mcp.portMode(MCP23017_PORT::A, 0); //Port A as ouput 23 | mcp.portMode(MCP23017_PORT::B, 0b11111111);//Port B as input 24 | 25 | mcp.interruptMode(MCP23017_INTMODE::SEPARATED); 26 | mcp.interrupt(MCP23017_PORT::B, FALLING); 27 | 28 | mcp.writeRegister(MCP23017_REGISTER::GPIOA, 0x00); 29 | mcp.writeRegister(MCP23017_REGISTER::GPIOB, 0x00); 30 | 31 | mcp.clearInterrupts(); 32 | attachInterrupt(1, userInput, FALLING); 33 | */ 34 | device.digitalWrite(pin, state); 35 | } 36 | 37 | bool IO_Digital::digitalRead(uint8_t pin) { 38 | return device.digitalRead(pin); 39 | } 40 | 41 | -------------------------------------------------------------------------------- /src/io_digital.h: -------------------------------------------------------------------------------- 1 | #ifndef io_digital_h 2 | #define io_digital_h 3 | 4 | #include 5 | #include 6 | 7 | class IO_Digital { 8 | public: 9 | IO_Digital(TwoWire& w); 10 | void setPinMode(uint8_t pin, bool input); 11 | void digitalWrite(uint8_t pin, bool state); 12 | bool digitalRead(uint8_t pin); 13 | 14 | private: 15 | TwoWire& _Wire; 16 | MCP23017 device; 17 | }; 18 | 19 | #endif -------------------------------------------------------------------------------- /src/log_store.cpp: -------------------------------------------------------------------------------- 1 | #include "log_store.h" 2 | #include "utils.h" 3 | 4 | // https://github.com/espressif/arduino-esp32/blob/master/libraries/SPIFFS/examples/SPIFFS_time/SPIFFS_time.ino 5 | 6 | /** 7 | * Lowlevel class for writing log messages to serial output, but also to store them for later retreival with method getLogmessages. 8 | */ 9 | LogStore::LogStore() : HardwareSerial(0) { 10 | current_line.reserve(100); 11 | } 12 | 13 | size_t LogStore::write(uint8_t c) { 14 | auto result = HardwareSerial::write(c); 15 | 16 | if (result > 0) { 17 | writeInternal(c); 18 | } 19 | 20 | return result; 21 | } 22 | 23 | size_t LogStore::write(const uint8_t* buffer, size_t size) { 24 | auto result = HardwareSerial::write(buffer, size); 25 | 26 | if (result > 0) { 27 | for (int i = 0; i < result; i++) { 28 | writeInternal(buffer[i]); 29 | } 30 | } 31 | 32 | return result; 33 | } 34 | 35 | logmessage_response LogStore::getLogMessages() { 36 | logmessage_response response = { 37 | total: current_lastnr, 38 | messages: log_messages 39 | }; 40 | 41 | return response; 42 | } 43 | 44 | void LogStore::writeInternal(uint8_t c) { 45 | 46 | if (c != '\n') { 47 | current_line.concat((char)c); 48 | } else { 49 | if (log_messages.size() >= Definitions::MAX_LOGMESSAGES) { 50 | log_messages.pop_front(); 51 | } 52 | 53 | log_messages.emplace_back(); 54 | auto& newMsg = log_messages.back(); 55 | 56 | newMsg.id = ++current_lastnr; 57 | 58 | if (Utils::isTimeAvailable) { 59 | newMsg.message = Utils::getTime("%H:%M:%S") + " " + current_line; 60 | current_line = ""; 61 | } 62 | else { 63 | newMsg.message = std::move(current_line); 64 | current_line.reserve(100); 65 | } 66 | } 67 | } 68 | -------------------------------------------------------------------------------- /src/log_store.h: -------------------------------------------------------------------------------- 1 | #ifndef _log_store_h 2 | #define _log_store_h 3 | 4 | #include 5 | #include 6 | #include "HardwareSerial.h" 7 | #include "definitions.h" 8 | 9 | struct logmessage { 10 | uint16_t id; 11 | String message; 12 | }; 13 | 14 | struct logmessage_response { 15 | const uint16_t total; 16 | const std::deque& messages; 17 | }; 18 | 19 | class LogStore : public HardwareSerial { 20 | public: 21 | LogStore(); 22 | size_t write(uint8_t) override; 23 | size_t write(const uint8_t* buffer, size_t size) override; 24 | logmessage_response getLogMessages(); 25 | 26 | private: 27 | std::deque log_messages; 28 | String current_line; 29 | uint16_t current_lastnr = 0; 30 | void writeInternal(uint8_t c); 31 | }; 32 | 33 | extern LogStore LoggingSerial; 34 | 35 | #endif -------------------------------------------------------------------------------- /src/lora.cpp: -------------------------------------------------------------------------------- 1 | Test code : 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | AsyncWebServer server(80); 8 | //AsyncWebSocket ws("/ws"); 9 | 10 | String outgoing; // outgoing message 11 | 12 | byte msgCount = 0; // count of outgoing messages 13 | byte localAddress = 0xBB; // address of this device 14 | byte destination = 0xFF; // destination to send to 15 | long lastSendTime = 0; // last send time 16 | int interval = 2000; // interval between sends 17 | 18 | const char *ssid = "BlackFox"; 19 | const char *password = "a/@1234567"; 20 | 21 | void setup() 22 | { 23 | Serial.begin(115200); 24 | WiFi.begin(ssid, password); 25 | 26 | while (WiFi.status() != WL_CONNECTED) 27 | { 28 | delay(1000); 29 | Serial.println("Connecting to WiFi.."); 30 | } 31 | 32 | Serial.println(WiFi.localIP()); 33 | 34 | server.on("/hello", HTTP_GET, [](AsyncWebServerRequest *request) { 35 | String message = "HeLoRa World! web"; // send a message 36 | sendMessage(message); 37 | request->send(200, "text/plain", "Hello World"); 38 | }); 39 | 40 | while (!Serial) 41 | ; 42 | 43 | Serial.println("LoRa Duplex"); 44 | 45 | // override the default CS, reset, and IRQ pins (optional) 46 | LoRa.setPins(13, 17, -1); // set CS, reset, IRQ pin 47 | 48 | if (!LoRa.begin(433E6)) 49 | { // initialize ratio at 915 MHz 50 | Serial.println("LoRa init failed. Check your connections."); 51 | while (true) 52 | ; // if failed, do nothing 53 | } 54 | server.begin(); 55 | Serial.println("LoRa init succeeded."); 56 | } 57 | 58 | void loop() 59 | { 60 | if (millis() - lastSendTime > interval) 61 | { 62 | String message = "HeLoRa World!"; // send a message 63 | sendMessage(message); 64 | Serial.println("Sending " + message); 65 | lastSendTime = millis(); // timestamp the message 66 | interval = random(2000) + 1000; // 2-3 seconds 67 | } 68 | 69 | // parse for a packet, and call onReceive with the result: 70 | onReceive(LoRa.parsePacket()); 71 | } 72 | 73 | void sendMessage(String outgoing) 74 | { 75 | LoRa.beginPacket(); // start packet 76 | LoRa.write(destination); // add destination address 77 | LoRa.write(localAddress); // add sender address 78 | LoRa.write(msgCount); // add message ID 79 | LoRa.write(outgoing.length()); // add payload length 80 | LoRa.print(outgoing); // add payload 81 | LoRa.endPacket(); // finish packet and send it 82 | msgCount++; // increment message ID 83 | } 84 | 85 | void onReceive(int packetSize) 86 | { 87 | if (packetSize == 0) 88 | return; // if there's no packet, return 89 | 90 | // read packet header bytes: 91 | int recipient = LoRa.read(); // recipient address 92 | byte sender = LoRa.read(); // sender address 93 | byte incomingMsgId = LoRa.read(); // incoming msg ID 94 | byte incomingLength = LoRa.read(); // incoming msg length 95 | 96 | String incoming = ""; 97 | 98 | while (LoRa.available()) 99 | { 100 | incoming += (char)LoRa.read(); 101 | } 102 | 103 | if (incomingLength != incoming.length()) 104 | { // check length for error 105 | Serial.println("error: message length does not match length"); 106 | return; // skip rest of function 107 | } 108 | 109 | // if the recipient isn't this device or broadcast, 110 | if (recipient != localAddress && recipient != 0xFF) 111 | { 112 | Serial.println("This message is not for me."); 113 | return; // skip rest of function 114 | } 115 | 116 | // if message is for this device, or broadcast, print details: 117 | Serial.println("Received from: 0x" + String(sender, HEX)); 118 | Serial.println("Sent to: 0x" + String(recipient, HEX)); 119 | Serial.println("Message ID: " + String(incomingMsgId)); 120 | Serial.println("Message length: " + String(incomingLength)); 121 | Serial.println("Message: " + incoming); 122 | Serial.println("RSSI: " + String(LoRa.packetRssi())); 123 | Serial.println("Snr: " + String(LoRa.packetSnr())); 124 | Serial.println(); 125 | } -------------------------------------------------------------------------------- /src/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include "definitions.h" 7 | #include "configuration.h" 8 | #include "log_store.h" 9 | #include "resources.h" 10 | #include "io_analog.h" 11 | #include "io_digital.h" 12 | #include "io_accelerometer/io_accelerometer.h" 13 | #include "wheel_controller.h" 14 | #include "wheel.h" 15 | #include "cutter.h" 16 | #include "battery.h" 17 | #include "gps.h" 18 | #include "sonar.h" 19 | #include "state_controller.h" 20 | #include "mowing_schedule.h" 21 | #include "dockingstation/dockingstation.h" 22 | 23 | /* 24 | * Software for controlling a LIAM robotmower using a ESP-32 microcontroller. 25 | * 26 | * Congratulation, you have just found the starting point of the program! 27 | */ 28 | 29 | // Give us an warning if main loop is delayed more than this value. This could be an indication of long hidden "delay" calls in our code. 30 | const uint32_t LOOP_DELAY_WARNING = 500000; // 500 ms 31 | // Don't spam us with warnings, wait this period before issuing a new warning 32 | const uint32_t LOOP_DELAY_WARNING_COOLDOWN = 10000000; // 10 sec 33 | 34 | // Setup references between all classes. 35 | LogStore logstore; 36 | IO_Analog io_analog; 37 | IO_Digital io_digital(Wire); 38 | IO_Accelerometer io_accelerometer(Wire); 39 | Wheel leftWheel(1, Definitions::LEFT_WHEEL_MOTOR_PIN, Definitions::LEFT_WHEEL_MOTOR_DIRECTION_PIN, Definitions::LEFT_WHEEL_ODOMETER_PIN, Definitions::LEFT_WHEEL_MOTOR_INVERTED, Definitions::LEFT_WHEEL_MOTOR_SPEED); 40 | Wheel rightWheel(2, Definitions::RIGHT_WHEEL_MOTOR_PIN, Definitions::RIGHT_WHEEL_MOTOR_DIRECTION_PIN, Definitions::RIGHT_WHEEL_ODOMETER_PIN, Definitions::RIGHT_WHEEL_MOTOR_INVERTED, Definitions::RIGHT_WHEEL_MOTOR_SPEED); 41 | WheelController wheelController(leftWheel, rightWheel); 42 | Cutter cutter(io_analog); 43 | GPS gps; 44 | Sonar sonar; 45 | Battery battery(io_analog, Wire); 46 | MowingSchedule mowingSchedule; 47 | Resources resources(wheelController, cutter, battery, gps, sonar, io_accelerometer, logstore, mowingSchedule); 48 | StateController stateController(resources); 49 | Dockingstation dockingstation(stateController, resources); 50 | 51 | uint64_t loopDelayWarningTime; 52 | 53 | /** 54 | * Scan I2C buss for available devices and print result to console. 55 | */ 56 | void scan_I2C() { 57 | byte error, address; 58 | int devices = 0; 59 | 60 | Log.trace(F("Scanning for I2C devices..." CR)); 61 | 62 | for (address = 1; address < 127; address++ ) { 63 | 64 | Wire.beginTransmission(address); 65 | error = Wire.endTransmission(); 66 | 67 | if (error == 0) { 68 | Log.notice(F("I2C device found at address %X" CR), address); 69 | devices++; 70 | } else if (error == 4) { 71 | Log.warning(F("Unknown error at address %X" CR), address); 72 | } 73 | } 74 | 75 | if (devices == 0) { 76 | Log.warning(F("No I2C devices found" CR)); 77 | } else { 78 | Log.trace(F("scanning done." CR)); 79 | } 80 | } 81 | 82 | void check_SPI() { 83 | Log.notice(F("SPI pins, MOSI: %d, MISO: %d, SCK: %d, SS: %d." CR), MOSI, MISO, SCK, SS); 84 | } 85 | 86 | /** 87 | * Here we setup initial stuff, this is only run once. 88 | */ 89 | void setup() { 90 | 91 | pinMode(Definitions::FACTORY_RESET_PIN, INPUT_PULLUP); 92 | pinMode(Definitions::EMERGENCY_STOP_PIN, INPUT_PULLUP); 93 | 94 | //esp_log_level_set("*", ESP_LOG_DEBUG); 95 | 96 | logstore.begin(115200); 97 | Log.begin(LOG_LEVEL_NOTICE, &logstore, true); 98 | 99 | esp_chip_info_t chip_info; 100 | esp_chip_info(&chip_info); 101 | 102 | Log.notice(F(CR "=== %s v%s ===\nbuild time: %s %s\nCPU: %dx%d MHz\nFlash: %d KiB\nChip revision: %d\n=======================" CR CR), Definitions::APP_NAME, Definitions::APP_VERSION, __DATE__, __TIME__, chip_info.cores, ESP.getCpuFreqMHz(), ESP.getFlashChipSize() / 1024, chip_info.revision); 103 | 104 | Configuration::load(); 105 | 106 | // setup Log library to correct log level. 107 | Log.begin(Configuration::config.logLevel, &logstore, true); 108 | 109 | // setup I2C 110 | Wire.begin(Definitions::SDA_PIN, Definitions::SCL_PIN); 111 | Wire.setTimeout(500); // milliseconds 112 | Wire.setClock(400000); // 400 kHz I2C speed 113 | scan_I2C(); 114 | 115 | check_SPI(); 116 | 117 | // set up GPS 118 | //gps.init(); 119 | 120 | // start subsystems up 121 | delay(100); 122 | 123 | io_accelerometer.start(); 124 | dockingstation.start(); 125 | gps.start(); 126 | battery.start(); 127 | mowingSchedule.start(); 128 | 129 | auto lastState = Configuration::config.lastState; 130 | // initialize state controller, assume we are DOCKED unless there is a saved state. 131 | if (rtc_get_reset_reason(0) == SW_CPU_RESET && lastState.length() > 0) { 132 | Log.notice(F("Returning to last state \"%s\" after software crash!" CR), lastState.c_str()); 133 | stateController.setState(lastState); 134 | } else { 135 | stateController.setState(Definitions::MOWER_STATES::DOCKED); 136 | } 137 | } 138 | 139 | // 140 | // Main program loop 141 | // 142 | void loop() { 143 | uint64_t loopStartTime = esp_timer_get_time(); 144 | 145 | if (digitalRead(Definitions::FACTORY_RESET_PIN) == LOW) { 146 | Log.notice(F("Factory reset by Switch" CR)); 147 | Configuration::wipe(); 148 | delay(1000); 149 | ESP.restart(); 150 | return; 151 | } 152 | 153 | if (Configuration::config.setupDone) { 154 | // always check if we are flipped. 155 | if (io_accelerometer.isFlipped() && stateController.getStateInstance()->getState() != Definitions::MOWER_STATES::FLIPPED) { 156 | stateController.setState(Definitions::MOWER_STATES::FLIPPED); 157 | } 158 | 159 | if (digitalRead(Definitions::EMERGENCY_STOP_PIN) == LOW) { 160 | stateController.setState(Definitions::MOWER_STATES::STOP);; 161 | } 162 | 163 | sonar.process(); 164 | stateController.getStateInstance()->process(); 165 | wheelController.process(); 166 | cutter.process(); 167 | } 168 | 169 | uint64_t currentTime = esp_timer_get_time(); 170 | uint32_t loopDelay = currentTime - loopStartTime; 171 | 172 | if (loopDelay > LOOP_DELAY_WARNING && (currentTime - loopDelayWarningTime) > LOOP_DELAY_WARNING_COOLDOWN) { 173 | loopDelayWarningTime = currentTime; 174 | 175 | Log.warning(F("Main loop running slow due to long delay(%l us)! Make sure thread is not blocked by delays()." CR), (uint32_t)loopDelay); 176 | } 177 | 178 | // small delay on purpose, to reduce load on CPU 179 | delay(1); 180 | } 181 | -------------------------------------------------------------------------------- /src/mowing_schedule.cpp: -------------------------------------------------------------------------------- 1 | #include "mowing_schedule.h" 2 | #include "configuration.h" 3 | #include 4 | #include 5 | #include 6 | 7 | 8 | MowingSchedule::MowingSchedule() {} 9 | 10 | /** 11 | * Adds a new entry to the schedule list. 12 | * @param activeWeekdays represent the seven days in a week (MUST always sized seven) 13 | * @param time to start mowing, the format MUST be "HH:MM" 14 | * @param time to stop mowing, the format MUST be "HH:MM" 15 | * @return -1 malformated activeWeekdays, -2 malformated startTime, -3 malformated stopTime, -4 too many entries. 0 or greater = success 16 | */ 17 | int8_t MowingSchedule::addScheduleEntry(std::deque activeWeekdays, String startTime, String stopTime) { 18 | const std::regex timeRegex("(00|01|02|03|04|05|06|07|08|09|10|11|12|13|14|15|16|17|18|19|20|21|22|23):(0|1|2|3|4|5)\\d"); 19 | 20 | if (mowingSchedule.size() >= 10) { 21 | return -4; 22 | } 23 | 24 | if (activeWeekdays.size() < 7 || activeWeekdays.size() > 7) { 25 | return -1; 26 | } 27 | 28 | if (!std::regex_match(startTime.c_str(), timeRegex)) { 29 | return -2; 30 | } 31 | 32 | if (!std::regex_match(stopTime.c_str(), timeRegex)) { 33 | return -3; 34 | } 35 | 36 | scheduleEntry entry; 37 | entry.activeWeekdays = activeWeekdays; 38 | entry.startTime = startTime; 39 | entry.stopTime = stopTime; 40 | 41 | mowingSchedule.push_front(entry); 42 | saveSchedulesToFlash(); 43 | 44 | return 1; 45 | } 46 | 47 | const std::deque& MowingSchedule::getScheduleEntries() const { 48 | return mowingSchedule; 49 | } 50 | 51 | /** 52 | * Removes an entry from the list 53 | * @param position the position of the entry in the list that should be removed (first position = 0) 54 | */ 55 | void MowingSchedule::removeScheduleEntry(uint8_t position) { 56 | if (position < mowingSchedule.size()) { 57 | mowingSchedule.erase(mowingSchedule.begin() + position); 58 | saveSchedulesToFlash(); 59 | } 60 | } 61 | 62 | /** 63 | * Override schedule to force mower to start mowing outside of schedule, this is used when manually launching mower from API. 64 | */ 65 | void MowingSchedule::setManualMowingOverride(bool enable) { 66 | manualMowingOverride = enable; 67 | } 68 | 69 | /** 70 | * Check if the mower should mow now, according to the mowing schedule and the current time. 71 | */ 72 | bool MowingSchedule::isTimeToMow() { 73 | 74 | if (manualMowingOverride) { 75 | return true; 76 | } 77 | 78 | struct tm timeinfo; 79 | 80 | if (!getLocalTime(&timeinfo, 200)) { // tries for 200 ms 81 | return false; 82 | } 83 | 84 | // fix day-of-week to follow ISO-8601 85 | int8_t dayOfWeek = timeinfo.tm_wday == 0 ? 6 : timeinfo.tm_wday - 1; 86 | 87 | for (auto schedule : mowingSchedule) { 88 | 89 | if (schedule.activeWeekdays[dayOfWeek]) { 90 | int currentTimeInMinutes = timeinfo.tm_hour * 60 + timeinfo.tm_min; 91 | int startTimeInMinutes = schedule.startTime.substring(0, 2).toInt() * 60 + schedule.startTime.substring(3).toInt(); // turn string, like "08:45", into minutes. 92 | int stopTimeInMinutes = schedule.stopTime.substring(0, 2).toInt() * 60 + schedule.stopTime.substring(3).toInt(); 93 | 94 | if (currentTimeInMinutes >= startTimeInMinutes && currentTimeInMinutes < stopTimeInMinutes) { 95 | return true; 96 | } 97 | } 98 | } 99 | 100 | return false; 101 | } 102 | 103 | void MowingSchedule::start() { 104 | loadSchedulesFromFlash(); 105 | } 106 | 107 | void MowingSchedule::loadSchedulesFromFlash() { 108 | 109 | mowingSchedule.clear(); 110 | 111 | Configuration::preferences.begin("liam-esp", false); 112 | auto jsonString = Configuration::preferences.getString("schedules", "[]"); 113 | 114 | DynamicJsonBuffer jsonBuffer(1200); 115 | JsonArray& root = jsonBuffer.parseArray(jsonString); 116 | 117 | if (root.success()) { 118 | 119 | for (auto schedule : root) { 120 | scheduleEntry entry; 121 | std::deque activeWeekdays; 122 | 123 | for (const auto& day : schedule["activeWeekdays"].as()) { 124 | activeWeekdays.push_back(day); 125 | } 126 | 127 | entry.activeWeekdays = activeWeekdays; 128 | entry.startTime = schedule["startTime"].as(); 129 | entry.stopTime = schedule["stopTime"].as(); 130 | 131 | mowingSchedule.push_back(entry); 132 | } 133 | 134 | Log.notice(F("Loaded %i schedules" CR), root.size()); 135 | } 136 | } 137 | 138 | void MowingSchedule::saveSchedulesToFlash() { 139 | // persist mowing schedules in case of power failure. 140 | DynamicJsonBuffer jsonBuffer(1200); 141 | JsonArray& root = jsonBuffer.createArray(); 142 | 143 | for (auto schedule : mowingSchedule) { 144 | JsonObject& entry = root.createNestedObject(); 145 | 146 | JsonArray& activeWeekdays = entry.createNestedArray("activeWeekdays"); 147 | 148 | for (auto day : schedule.activeWeekdays) { 149 | activeWeekdays.add(day); 150 | } 151 | 152 | entry["startTime"] = schedule.startTime; 153 | entry["stopTime"] = schedule.stopTime; 154 | } 155 | 156 | String jsonString; 157 | root.printTo(jsonString); 158 | 159 | Configuration::preferences.begin("liam-esp", false); 160 | Configuration::preferences.putString("schedules", jsonString); 161 | } 162 | -------------------------------------------------------------------------------- /src/mowing_schedule.h: -------------------------------------------------------------------------------- 1 | #ifndef _mowing_schedule_h 2 | #define _mowing_schedule_h 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | struct scheduleEntry { 9 | std::deque activeWeekdays; 10 | String startTime; 11 | String stopTime; 12 | }; 13 | 14 | class MowingSchedule { 15 | public: 16 | MowingSchedule(); 17 | int8_t addScheduleEntry(std::deque activeWeekdays, String startTime, String stopTime); 18 | const std::deque& getScheduleEntries() const; 19 | void removeScheduleEntry(uint8_t position); 20 | void setManualMowingOverride(bool enable); 21 | bool isTimeToMow(); 22 | void start(); 23 | 24 | private: 25 | bool manualMowingOverride = false; 26 | std::deque mowingSchedule; 27 | void saveSchedulesToFlash(); 28 | void loadSchedulesFromFlash(); 29 | }; 30 | 31 | #endif -------------------------------------------------------------------------------- /src/processable.h: -------------------------------------------------------------------------------- 1 | #ifndef _i_processable_h 2 | #define _i_processable_h 3 | 4 | /** 5 | * Interface for interactive classes that needs to update their internal state on every run of the main loop. 6 | */ 7 | class Processable { 8 | public: 9 | /** 10 | * This method should be be called upon to update the objects internal state. 11 | */ 12 | virtual void process() = 0; 13 | }; 14 | 15 | #endif 16 | -------------------------------------------------------------------------------- /src/resources.h: -------------------------------------------------------------------------------- 1 | #ifndef resources_h 2 | #define resources_h 3 | 4 | #include "wheel_controller.h" 5 | #include "cutter.h" 6 | #include "battery.h" 7 | #include "gps.h" 8 | #include "sonar.h" 9 | #include "configuration.h" 10 | #include "io_accelerometer/io_accelerometer.h" 11 | #include "log_store.h" 12 | #include "mowing_schedule.h" 13 | 14 | 15 | /** 16 | * Container class for holding references to instances that should be shared between many classes. 17 | * This is so that we can reduce the number of parameters each method must take, but also making it easier to add additional references in the future. 18 | */ 19 | class Resources { 20 | public: 21 | Resources( WheelController& wheelController, 22 | Cutter& cutter, 23 | Battery& battery, 24 | GPS& gps, 25 | Sonar& sonar, 26 | IO_Accelerometer& accelerometer, 27 | LogStore& logStore, 28 | MowingSchedule& mowingSchedule) 29 | : wheelController(wheelController), 30 | cutter(cutter), 31 | battery(battery), 32 | gps(gps), 33 | sonar(sonar), 34 | accelerometer(accelerometer), 35 | logStore(logStore), 36 | mowingSchedule(mowingSchedule) { } 37 | 38 | WheelController& wheelController; 39 | Cutter& cutter; 40 | Battery& battery; 41 | GPS& gps; 42 | Sonar& sonar; 43 | IO_Accelerometer& accelerometer; 44 | LogStore& logStore; 45 | MowingSchedule& mowingSchedule; 46 | }; 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /src/scheduler/scheduler.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "scheduler.h" 4 | 5 | /** 6 | * Constructor for a function scheduler. 7 | * @param inSeries if true the delay time for a scheduled function will be releative the previous scheduled function. If false the delay will be relative the current time when the function was scheduled. 8 | */ 9 | Scheduler::Scheduler(bool inSeries) : in_series(inSeries) { } 10 | 11 | /** 12 | * Schedule a function to execute after the specified delay. 13 | * The function will be executed only once, unless the repeat-flag has been set. 14 | * @param fn function to be scheduled for later execution. 15 | * @param delay delay in milliseconds. 16 | * @param repeat when the delay has been reached and the function has been executed, then reschedule the function for another delay milliseconds. 17 | */ 18 | uint16_t Scheduler::schedule(const std::function fn, uint32_t delay, bool repeat) { 19 | 20 | // TODO: could this be a inspiration/replacement? https://github.com/espressif/arduino-esp32/pull/1516 21 | scheduled_fn_t it; 22 | it.id = ++task_counter; 23 | it.func = fn; 24 | it.repeat = repeat; 25 | 26 | if (in_series && !scheduled_fn_list.empty()) { 27 | it.startMillis = scheduled_fn_list.back().startMillis; 28 | it.delay = scheduled_fn_list.back().delay + delay; 29 | } else { 30 | it.startMillis = millis(); 31 | it.delay = delay; 32 | } 33 | 34 | scheduled_fn_list.push_back(std::move(it)); 35 | 36 | // TODO: sort list if not in_series. delay and startMillis must be taken into account releative the current millis! 37 | /*if (!in_series) { 38 | scheduled_fn_list.sort([](const scheduled_fn_t &f, const scheduled_fn_t &s) { 39 | return f.delay < s.delay; 40 | }); 41 | }*/ 42 | 43 | return task_counter; 44 | } 45 | 46 | /** 47 | * Unschedule a already scheduled function. 48 | * @param id id of already scheduled function. 49 | */ 50 | void Scheduler::unschedule(uint16_t id) { 51 | scheduled_fn_list.erase( 52 | find_if(scheduled_fn_list.begin(), scheduled_fn_list.end(), 53 | [id](const scheduled_fn_t& i) { 54 | return i.id == id; 55 | }), 56 | scheduled_fn_list.end() 57 | ); 58 | } 59 | 60 | /** 61 | * Returns whether no functions has been scheduled. 62 | */ 63 | bool Scheduler::isEmpty() { 64 | return scheduled_fn_list.empty(); 65 | } 66 | 67 | /** 68 | * Remove all scheduled functions. 69 | */ 70 | void Scheduler::clear() { 71 | scheduled_fn_list.clear(); 72 | } 73 | 74 | /** 75 | * Method should be called upon repeatedly and requent to execute the functions that may have reached their delay time. 76 | */ 77 | void Scheduler::process() { 78 | for (auto i = scheduled_fn_list.begin(); i != scheduled_fn_list.end();) { 79 | // Check if delay has expired. Handles timer overflow. millis() on ESP8266 has a roll over of 72 minutes. (Based on microsecond tick.) 80 | if (millis() - (*i).startMillis >= (*i).delay) { 81 | // execute scheduled function. 82 | (*i).func(); 83 | 84 | // reschedule if set to repeat. 85 | 86 | if ((*i).repeat) { 87 | if (in_series) { 88 | (*i).startMillis = scheduled_fn_list.back().startMillis; 89 | (*i).delay = scheduled_fn_list.back().delay + (*i).delay; 90 | } else { 91 | (*i).startMillis = millis(); 92 | } 93 | // repush it to the last postition in the list. 94 | scheduled_fn_list.push_back((*i)); 95 | } 96 | 97 | // remove from current position in list. 98 | i = scheduled_fn_list.erase(i); 99 | 100 | } else { 101 | ++i; 102 | } 103 | } 104 | } 105 | -------------------------------------------------------------------------------- /src/scheduler/scheduler.h: -------------------------------------------------------------------------------- 1 | #ifndef _scheduler_util_h 2 | #define _scheduler_util_h 3 | 4 | #include 5 | #include 6 | 7 | struct scheduled_fn_t 8 | { 9 | bool repeat; 10 | uint16_t id; 11 | uint16_t delay; 12 | uint32_t startMillis; 13 | std::function func; 14 | }; 15 | 16 | class Scheduler { 17 | public: 18 | Scheduler(bool inSeries = false); 19 | uint16_t schedule(const std::function fn, uint32_t time, bool repeat = false); 20 | void unschedule(uint16_t id); 21 | bool isEmpty(); 22 | void clear(); 23 | void process(); 24 | 25 | private: 26 | std::list scheduled_fn_list; 27 | uint16_t task_counter = 0; 28 | bool in_series = false; 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/sonar.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "sonar.h" 4 | #include "utils.h" 5 | #include "definitions.h" 6 | 7 | // Idea taken from https://www.instructables.com/id/Non-blocking-Ultrasonic-Sensor-for-Arduino/ 8 | 9 | /** 10 | * Class for interfacing with a ultrasound sonar sensor, used for detecting obstacles around the mower before we bump into them. 11 | * Compatible sensors are HC-SR04. SRF06 is NOT supported since it's too slow. 12 | */ 13 | Sonar::Sonar() { 14 | // define available sensors... 15 | SonarDevice sonarFront; 16 | sonarFront.ping_pin = Definitions::SONAR_FRONT_PING_PIN; 17 | sonarFront.sense_pin = Definitions::SONAR_FRONT_SENSE_PIN; 18 | pinMode(sonarFront.ping_pin, OUTPUT); 19 | pinMode(sonarFront.sense_pin, INPUT); 20 | attachInterrupt(sonarFront.sense_pin, std::bind(&Sonar::onPing, this), CHANGE); 21 | } 22 | 23 | void Sonar::ping(SonarDevice device) { 24 | 25 | if (!pingInProgress) { 26 | 27 | pingInProgress = true; 28 | startTime = micros(); // just set it, we will update it later in ISR to be more current. This is needed to check for timeouts in process() 29 | 30 | digitalWrite(device.ping_pin, LOW); // Set the trigger pin low, should already be low, but this will make sure it is. 31 | delayMicroseconds(4); // Wait for pin to go low. 32 | digitalWrite(device.ping_pin, HIGH); // Set trigger pin high, this tells the sensor to send out a ping. 33 | delayMicroseconds(10); // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS. 34 | digitalWrite(device.ping_pin, LOW); // Set trigger pin back to low. 35 | 36 | } 37 | } 38 | 39 | void IRAM_ATTR Sonar::onPing() { 40 | auto time = micros(); 41 | 42 | portENTER_CRITICAL_ISR(&mux); 43 | 44 | // check if we went from HIGH to LOW, or from LOW to HIGH 45 | switch(digitalRead(sonarFront.sense_pin)) { 46 | case HIGH: 47 | // store starttime when we just received ping response 48 | // _______________.... (duration, longer pule = obstacle far away) 49 | // | 50 | //____| 51 | startTime = time; 52 | break; 53 | case LOW: 54 | // store ping duration in samplelist for current sonar 55 | // ____ 56 | // | 57 | // |______________.... (when signal goes LOW, calculate duration of pulse and store as one sample) 58 | auto distance = (time - startTime) / 57; // divide with 57 to get distance in centimeters from microseconds. 59 | 60 | if (distance <= Definitions::SONAR_MAXDISTANCE) { 61 | sonarFront.sampleDistances[sonarFront.sampleIndex] = distance; 62 | sonarFront.sampleIndex = (sonarFront.sampleIndex + 1) % (sizeof(sonarFront.sampleDistances) / sizeof(uint16_t)); 63 | } 64 | 65 | pingInProgress = false; 66 | break; 67 | } 68 | 69 | portEXIT_CRITICAL_ISR(&mux); 70 | } 71 | 72 | void Sonar::process() { 73 | 74 | portENTER_CRITICAL(&mux); 75 | 76 | if (pingInProgress && (micros() - startTime) > 30000L) { 77 | // if we have not received an response within 30ms since ping started then either our startsignal was not detected by the sonar-sensor or no obstacle was detected within 4,5 meters range. 78 | pingInProgress = false; 79 | } 80 | 81 | if (!pingInProgress) { 82 | sonarFront.distance = Utils::calculateMedian(sonarFront.sampleDistances); 83 | // currentSonar = (currentSonar + 1) % sonars.size(); 84 | // Log.notice("t1: %d, t2: %d, d: %d %d %d %d %d" CR, test1, test2, sonar.sampleDistances[0], sonar.sampleDistances[1], sonar.sampleDistances[2], sonar.sampleDistances[3], sonar.sampleDistances[4]); 85 | 86 | ping(sonarFront); 87 | } 88 | portEXIT_CRITICAL(&mux); 89 | } 90 | 91 | /** 92 | * Get distances from mower to closest detected obstacle (in centimeters) 93 | */ 94 | SonarDistances Sonar::getObstacleDistances() { 95 | 96 | portENTER_CRITICAL(&mux); 97 | 98 | SonarDistances distances; 99 | distances.frontDistance = sonarFront.distance; 100 | 101 | portEXIT_CRITICAL(&mux); 102 | 103 | return distances; 104 | } 105 | -------------------------------------------------------------------------------- /src/sonar.h: -------------------------------------------------------------------------------- 1 | #ifndef _sonar_h 2 | #define _sonar_h 3 | 4 | #include 5 | #include "processable.h" 6 | 7 | struct SonarDevice { 8 | uint8_t ping_pin; 9 | uint8_t sense_pin; 10 | uint8_t sampleIndex = 0; 11 | uint16_t sampleDistances[5] = { 0, 0, 0, 0, 0 }; // Numer of samples before calculating distance, higher value means we get less affected of false readings (like reflecting grass) but consuming more memory and less responsive to sudden obstacles. 12 | uint16_t distance = 0; 13 | }; 14 | 15 | struct SonarDistances { 16 | uint16_t frontDistance = 0; 17 | }; 18 | 19 | class Sonar : public Processable { 20 | public: 21 | 22 | Sonar(); 23 | SonarDistances getObstacleDistances(); 24 | /* Internal use only! */ 25 | void process(); 26 | 27 | private: 28 | volatile boolean pingInProgress = false; 29 | volatile unsigned long startTime = 0; 30 | SonarDevice sonarFront; 31 | portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED; 32 | void ping(SonarDevice device); 33 | void IRAM_ATTR onPing(); 34 | }; 35 | 36 | #endif 37 | -------------------------------------------------------------------------------- /src/state_controller.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "state_controller.h" 3 | #include "states/docked.h" 4 | #include "states/launching.h" 5 | #include "states/mowing.h" 6 | #include "states/docking.h" 7 | #include "states/charging.h" 8 | #include "states/stuck.h" 9 | #include "states/flipped.h" 10 | #include "states/manual.h" 11 | #include "states/stop.h" 12 | #include "states/test.h" 13 | #include "configuration.h" 14 | 15 | StateController::StateController(Resources& resources) : resources(resources) { 16 | stateLookup[Definitions::MOWER_STATES::DOCKED] = new Docked(Definitions::MOWER_STATES::DOCKED, *this, resources); 17 | stateLookup[Definitions::MOWER_STATES::LAUNCHING] = new Launching(Definitions::MOWER_STATES::LAUNCHING, *this, resources); 18 | stateLookup[Definitions::MOWER_STATES::MOWING] = new Mowing(Definitions::MOWER_STATES::MOWING, *this, resources); 19 | stateLookup[Definitions::MOWER_STATES::DOCKING] = new Docking(Definitions::MOWER_STATES::DOCKING, *this, resources); 20 | stateLookup[Definitions::MOWER_STATES::CHARGING] = new Charging(Definitions::MOWER_STATES::CHARGING, *this, resources); 21 | stateLookup[Definitions::MOWER_STATES::STUCK] = new Stuck(Definitions::MOWER_STATES::STUCK, *this, resources); 22 | stateLookup[Definitions::MOWER_STATES::FLIPPED] = new Flipped(Definitions::MOWER_STATES::FLIPPED, *this, resources); 23 | stateLookup[Definitions::MOWER_STATES::MANUAL] = new Manual(Definitions::MOWER_STATES::MANUAL, *this, resources); 24 | stateLookup[Definitions::MOWER_STATES::STOP] = new Stop(Definitions::MOWER_STATES::STOP, *this, resources); 25 | stateLookup[Definitions::MOWER_STATES::TEST] = new Test(Definitions::MOWER_STATES::TEST, *this, resources); 26 | } 27 | 28 | void StateController::setState(Definitions::MOWER_STATES newState) { 29 | // only set state if not same 30 | if (currentStateInstance == nullptr || currentStateInstance->getState() != newState) { 31 | // save reference to previous state before we switching to a new one. We check for nullptr because the first time there will be no previous state. 32 | Definitions::MOWER_STATES previousState = currentStateInstance == nullptr ? newState : currentStateInstance->getState(); 33 | 34 | currentStateInstance = stateLookup[newState]; 35 | currentStateInstance->selected(previousState); 36 | 37 | Log.notice("New state: %s" CR, currentStateInstance->getStateName()); 38 | // save state in case we reboot 39 | Configuration::config.lastState = currentStateInstance->getStateName(); 40 | Configuration::save(); 41 | 42 | //resources.wlan.publish_mqtt(currentStateInstance->getStateName(), "/state"); 43 | } 44 | } 45 | 46 | void StateController::setState(String newState) { 47 | // switch-cases don't support String and std::unordered_map does not support String, so we are stuck with if-else. 48 | if (newState == "DOCKED") { 49 | setState(Definitions::MOWER_STATES::DOCKED); 50 | } else if (newState == "LAUNCHING") { 51 | setState(Definitions::MOWER_STATES::LAUNCHING); 52 | } else if (newState == "MOWING") { 53 | setState(Definitions::MOWER_STATES::MOWING); 54 | } else if (newState == "DOCKING") { 55 | setState(Definitions::MOWER_STATES::DOCKING); 56 | } else if (newState == "CHARGING") { 57 | setState(Definitions::MOWER_STATES::CHARGING); 58 | } else if (newState == "STUCK") { 59 | setState(Definitions::MOWER_STATES::STUCK); 60 | } else if (newState == "FLIPPED") { 61 | setState(Definitions::MOWER_STATES::FLIPPED); 62 | } else if (newState == "MANUAL") { 63 | setState(Definitions::MOWER_STATES::MANUAL); 64 | } else if (newState == "STOP") { 65 | setState(Definitions::MOWER_STATES::STOP); 66 | } else if (newState == "TEST") { 67 | setState(Definitions::MOWER_STATES::TEST); 68 | } else { 69 | Log.warning("state \"%s\" unknown, ignoring in setState." CR, newState); 70 | } 71 | } 72 | 73 | bool StateController::setUserChangableState(String newState) { 74 | if (newState == "LAUNCHING") { 75 | // set scheduler to manual override otherwise it will reset the state back to DOCKING since we could be outside the time-schedule. 76 | resources.mowingSchedule.setManualMowingOverride(true); 77 | setState(Definitions::MOWER_STATES::LAUNCHING); 78 | } else if (newState == "MOWING") { 79 | setState(Definitions::MOWER_STATES::MOWING); 80 | } else if (newState == "DOCKING") { 81 | setState(Definitions::MOWER_STATES::DOCKING); 82 | } else if (newState == "STOP") { 83 | setState(Definitions::MOWER_STATES::STOP); 84 | } else if (newState == "TEST") { 85 | setState(Definitions::MOWER_STATES::TEST); 86 | } else { 87 | Log.notice(F("State \"%s\" not available for user to change." CR), newState); 88 | return false; 89 | } 90 | 91 | return true; 92 | } 93 | 94 | AbstractState* StateController::getStateInstance() { 95 | return currentStateInstance; 96 | } 97 | -------------------------------------------------------------------------------- /src/state_controller.h: -------------------------------------------------------------------------------- 1 | #ifndef _statecontroller_h 2 | #define _statecontroller_h 3 | 4 | #include 5 | #include // NOTE: needed to fix the following error: "Arduino.h:253:18: error: expected unqualified-id before '(' token". 6 | #include "definitions.h" 7 | #include "resources.h" 8 | #include 9 | #include "states/abstract_state.h" 10 | 11 | class StateController { 12 | public: 13 | StateController(Resources& resources); 14 | 15 | /** 16 | * Set new running state. 17 | */ 18 | void setState(Definitions::MOWER_STATES newState); 19 | 20 | /** 21 | * Set new running state. 22 | */ 23 | void setState(String newState); 24 | 25 | /** 26 | * Set new running state, only the states that allowed to be set externally are available. 27 | */ 28 | bool setUserChangableState(String newState); 29 | 30 | /** 31 | * Get running state instance. 32 | */ 33 | AbstractState* getStateInstance(); 34 | 35 | private: 36 | AbstractState* currentStateInstance; 37 | Resources& resources; 38 | // https://stackoverflow.com/questions/18837857/cant-use-enum-class-as-unordered-map-key 39 | struct EnumClassHash { 40 | template 41 | std::size_t operator()(T t) const { 42 | return static_cast(t); 43 | } 44 | }; 45 | std::unordered_map stateLookup; 46 | }; 47 | 48 | #endif 49 | -------------------------------------------------------------------------------- /src/states/abstract_state.h: -------------------------------------------------------------------------------- 1 | #ifndef _abstract_state_h 2 | #define _abstract_state_h 3 | 4 | #include "definitions.h" 5 | #include "resources.h" 6 | class StateController; 7 | 8 | /** 9 | * Abstract base class for all states to inherit from. 10 | */ 11 | class AbstractState { 12 | public: 13 | /** 14 | * Constructor with a reference to be able to communicate back to the state controller. 15 | */ 16 | AbstractState(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : myState(myState), stateController(stateController), resources(resources) {} 17 | 18 | /** 19 | * Get the state the class repressent. 20 | */ 21 | Definitions::MOWER_STATES getState() { 22 | return myState; 23 | } 24 | 25 | /** 26 | * Textual representation of the state, e.g. "MOWING". 27 | */ 28 | virtual const char* const getStateName(); 29 | 30 | /** 31 | * Should be called upon when this state has been selected as the current state. 32 | * @param lastState the previous running state. 33 | */ 34 | virtual void selected(Definitions::MOWER_STATES lastState) = 0; 35 | 36 | /** 37 | * This method will be executed on each turn in the event loop when this state is currently selected. 38 | */ 39 | virtual void process() = 0; 40 | 41 | protected: 42 | Definitions::MOWER_STATES myState; 43 | StateController& stateController; 44 | Resources& resources; 45 | }; 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /src/states/charging.cpp: -------------------------------------------------------------------------------- 1 | #include "charging.h" 2 | #include "state_controller.h" 3 | 4 | Charging::Charging(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Charging::selected(Definitions::MOWER_STATES lastState) { 9 | resources.cutter.stop(true); 10 | resources.wheelController.stop(); 11 | } 12 | 13 | void Charging::process() { 14 | 15 | if (resources.battery.isFullyCharged()) { 16 | stateController.setState(Definitions::MOWER_STATES::DOCKED); 17 | return; 18 | } 19 | 20 | } 21 | -------------------------------------------------------------------------------- /src/states/charging.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_charging_h 2 | #define _state_charging_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it has successfully docked with the charging station and have begun charging the batteries. 9 | */ 10 | class Charging : public AbstractState { 11 | public: 12 | Charging(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 13 | const char* const getStateName() { 14 | return "CHARGING"; 15 | } 16 | void selected(Definitions::MOWER_STATES lastState); 17 | void process(); 18 | }; 19 | 20 | #endif 21 | -------------------------------------------------------------------------------- /src/states/docked.cpp: -------------------------------------------------------------------------------- 1 | #include "docked.h" 2 | #include "state_controller.h" 3 | 4 | Docked::Docked(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Docked::selected(Definitions::MOWER_STATES lastState) { 9 | resources.cutter.stop(true); 10 | resources.wheelController.stop(); 11 | resources.mowingSchedule.setManualMowingOverride(false); // if docked then reset mowing override so that it will only launch on schedule. 12 | lastShouldMowCheck = millis(); 13 | } 14 | 15 | void Docked::process() { 16 | 17 | // if we receive current from the docking station, enter "charging"-state. 18 | if (resources.battery.isCharging()) { 19 | stateController.setState(Definitions::MOWER_STATES::CHARGING); 20 | return; 21 | } 22 | 23 | // Only check time to mow every other second, for performance reasons. 24 | if (lastShouldMowCheck + 2000 < millis()) { 25 | 26 | if (resources.mowingSchedule.isTimeToMow() && resources.battery.isFullyCharged()) { 27 | stateController.setState(Definitions::MOWER_STATES::LAUNCHING); 28 | } 29 | 30 | lastShouldMowCheck = millis(); 31 | } 32 | 33 | } 34 | -------------------------------------------------------------------------------- /src/states/docked.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_docked_h 2 | #define _state_docked_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it has successfully docked with the charging station. 9 | */ 10 | class Docked : public AbstractState { 11 | public: 12 | Docked(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 13 | const char* const getStateName() { 14 | return "DOCKED"; 15 | } 16 | void selected(Definitions::MOWER_STATES lastState); 17 | void process(); 18 | 19 | private: 20 | long lastShouldMowCheck = 0; 21 | }; 22 | 23 | #endif 24 | -------------------------------------------------------------------------------- /src/states/docking.cpp: -------------------------------------------------------------------------------- 1 | #include "docking.h" 2 | #include "state_controller.h" 3 | 4 | Docking::Docking(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Docking::selected(Definitions::MOWER_STATES lastState) { 9 | resources.cutter.stop(true); 10 | resources.wheelController.forward(0, 80, true); 11 | } 12 | 13 | void Docking::process() { 14 | 15 | if (resources.battery.isDocked()) { 16 | stateController.setState(Definitions::MOWER_STATES::DOCKED); 17 | return; 18 | } 19 | 20 | } 21 | -------------------------------------------------------------------------------- /src/states/docking.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_docking_h 2 | #define _state_docking_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it is heading home to dock with the charging station. 9 | * It could be low on batteries, or it's seeking shelter from the rain, or maybe it's just done mowing. 10 | */ 11 | class Docking : public AbstractState { 12 | public: 13 | Docking(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 14 | const char* const getStateName() { 15 | return "DOCKING"; 16 | } 17 | void selected(Definitions::MOWER_STATES lastState); 18 | void process(); 19 | }; 20 | 21 | #endif 22 | -------------------------------------------------------------------------------- /src/states/flipped.cpp: -------------------------------------------------------------------------------- 1 | #include "flipped.h" 2 | #include "state_controller.h" 3 | 4 | Flipped::Flipped(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) {} 5 | 6 | void Flipped::selected(Definitions::MOWER_STATES lastState) { 7 | // mower has flipped over/or are in a steep slope, stop cutter and wheels. 8 | previousState = lastState; 9 | resources.cutter.stop(true); 10 | resources.wheelController.stop(false); 11 | timer = millis(); 12 | } 13 | 14 | void Flipped::process() { 15 | // if mower has been unflipped for at least 4 seconds, then resume last state (usually mowing). 16 | if (resources.accelerometer.isFlipped()) { 17 | timer = millis(); 18 | } else { 19 | if (timer + 5000 < millis()) { 20 | stateController.setState(previousState); 21 | } 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /src/states/flipped.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_flipped_h 2 | #define _state_flipped_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it is flipped upside down or tilted too much. 9 | * This is a state that should not occur under normal conditions. 10 | */ 11 | class Flipped : public AbstractState { 12 | public: 13 | Flipped(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 14 | const char* const getStateName() { 15 | return "FLIPPED"; 16 | } 17 | void selected(Definitions::MOWER_STATES lastState); 18 | void process(); 19 | 20 | private: 21 | Definitions::MOWER_STATES previousState; 22 | uint32_t timer = 0; 23 | }; 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /src/states/launching.cpp: -------------------------------------------------------------------------------- 1 | #include "launching.h" 2 | #include "state_controller.h" 3 | 4 | Launching::Launching(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) {} 5 | 6 | void Launching::selected(Definitions::MOWER_STATES lastState) { 7 | resources.wheelController.backward(0, 50, true, Definitions::LAUNCH_DISTANCE, 8 | [this](void) -> void { 9 | resources.wheelController.turn(-180, [this](void) -> void { 10 | stateController.setState(Definitions::MOWER_STATES::MOWING); 11 | }); 12 | }); 13 | } 14 | 15 | void Launching::process() { 16 | } 17 | -------------------------------------------------------------------------------- /src/states/launching.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_launching_h 2 | #define _state_launching_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it is heading out from the charging station to begin mowing. 9 | */ 10 | class Launching : public AbstractState { 11 | public: 12 | Launching(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 13 | const char* const getStateName() { 14 | return "LAUNCHING"; 15 | } 16 | void selected(Definitions::MOWER_STATES lastState); 17 | void process(); 18 | }; 19 | 20 | #endif 21 | -------------------------------------------------------------------------------- /src/states/manual.cpp: -------------------------------------------------------------------------------- 1 | #include "manual.h" 2 | #include "state_controller.h" 3 | 4 | Manual::Manual(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Manual::selected(Definitions::MOWER_STATES lastState) { 9 | dockedDetectedTime = 0; 10 | } 11 | 12 | void Manual::process() { 13 | // if we drive manually and get disconnected from mower or mower loose WiFi connectivity, then stop mower from driving further. 14 | /*if (resources.wlan.getConnectedWebsocketClientsCount() == 0) { 15 | 16 | resources.cutter.stop(); 17 | 18 | auto wheelStatus = resources.wheelController.getStatus(); 19 | 20 | if (wheelStatus.leftWheelSpeed != 0 || wheelStatus.rightWheelSpeed != 0) { 21 | resources.wheelController.stop(true); 22 | } 23 | }*/ 24 | 25 | // if we have parked in dockingstation manually and mower detects it's docked, then enter docked-state after a short timeout. 26 | if (resources.battery.isDocked() && dockedDetectedTime == 0) { 27 | dockedDetectedTime = millis(); 28 | } 29 | 30 | if (millis() - dockedDetectedTime > 2000) { 31 | 32 | dockedDetectedTime = 0; 33 | 34 | if (resources.battery.isDocked()) { 35 | stateController.setState(Definitions::MOWER_STATES::DOCKED); 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /src/states/manual.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_manual_h 2 | #define _state_manual_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it has been set to manual driving mode from REST-API. User then has to change state again to resume automation. 9 | */ 10 | class Manual : public AbstractState { 11 | public: 12 | Manual(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 13 | const char* const getStateName() { 14 | return "MANUAL"; 15 | } 16 | void selected(Definitions::MOWER_STATES lastState); 17 | void process(); 18 | 19 | private: 20 | unsigned long dockedDetectedTime = 0; 21 | }; 22 | 23 | #endif 24 | -------------------------------------------------------------------------------- /src/states/mowing.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "mowing.h" 3 | #include "state_controller.h" 4 | 5 | Mowing::Mowing(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 6 | 7 | } 8 | 9 | void Mowing::selected(Definitions::MOWER_STATES lastState) { 10 | resources.cutter.start(); 11 | delay(2000); 12 | resources.wheelController.forward(0, 100, true); 13 | lastShouldMowCheck = millis(); 14 | } 15 | 16 | void Mowing::process() { 17 | 18 | if (resources.battery.needRecharge()) { 19 | stateController.setState(Definitions::MOWER_STATES::DOCKING); 20 | return; 21 | } 22 | 23 | // Only check time to mow every other second, for performance reasons. 24 | if (lastShouldMowCheck + 2000 < millis()) { 25 | if (!resources.mowingSchedule.isTimeToMow()) { 26 | stateController.setState(Definitions::MOWER_STATES::DOCKING); 27 | return; 28 | } 29 | 30 | lastShouldMowCheck = millis(); 31 | } 32 | 33 | if (resources.cutter.isFuseblown()) { 34 | stateController.setState(Definitions::MOWER_STATES::STUCK); 35 | Log.warning(F("Non-working cutter has been detected, loose wire or blown fuse?" CR)); 36 | return; 37 | } 38 | 39 | if (resources.cutter.isOverloaded()) { 40 | if (resources.wheelController.decreaseForwardSpeed()) { 41 | Log.verbose(F("Cutter overloaded, decreased speed of wheels.")); 42 | } 43 | } else { 44 | if (resources.wheelController.increaseForwardSpeed()) { 45 | Log.verbose(F("Cutterload back to normal, increased speed of wheels.")); 46 | } 47 | } 48 | } 49 | -------------------------------------------------------------------------------- /src/states/mowing.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_mowing_h 2 | #define _state_mowing_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | 8 | /** 9 | * State the mower enters when it is mowing. 10 | */ 11 | class Mowing : public AbstractState { 12 | public: 13 | Mowing(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 14 | const char* const getStateName() { 15 | return "MOWING"; 16 | } 17 | void selected(Definitions::MOWER_STATES lastState); 18 | void process(); 19 | 20 | private: 21 | long lastShouldMowCheck = 0; 22 | }; 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /src/states/stop.cpp: -------------------------------------------------------------------------------- 1 | #include "stop.h" 2 | #include "state_controller.h" 3 | 4 | Stop::Stop(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Stop::selected(Definitions::MOWER_STATES lastState) { 9 | resources.cutter.stop(true); 10 | resources.wheelController.stop(false); 11 | } 12 | 13 | void Stop::process() { 14 | 15 | } 16 | -------------------------------------------------------------------------------- /src/states/stop.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_stop_h 2 | #define _state_stop_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it is stopped by a user (by some clicking the stopbutton on mower or UI). 9 | */ 10 | class Stop : public AbstractState { 11 | public: 12 | Stop(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 13 | const char* const getStateName() { 14 | return "STOP"; 15 | } 16 | void selected(Definitions::MOWER_STATES lastState); 17 | void process(); 18 | }; 19 | 20 | #endif 21 | -------------------------------------------------------------------------------- /src/states/stuck.cpp: -------------------------------------------------------------------------------- 1 | #include "stuck.h" 2 | #include "state_controller.h" 3 | 4 | Stuck::Stuck(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources) { 5 | 6 | } 7 | 8 | void Stuck::selected(Definitions::MOWER_STATES lastState) { 9 | previousState = lastState; 10 | resources.cutter.stop(true); 11 | resources.wheelController.stop(false); 12 | retryTimer = millis(); 13 | } 14 | 15 | void Stuck::process() { 16 | 17 | if (Definitions::STUCK_RETRY_DELAY > 0 && (millis() - retryTimer > Definitions::STUCK_RETRY_DELAY * 1000)) { 18 | stateController.setState(previousState); 19 | } 20 | 21 | } 22 | -------------------------------------------------------------------------------- /src/states/stuck.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_stuck_h 2 | #define _state_stuck_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | 7 | /** 8 | * State the mower enters when it is stuck somewhere and failes to operate properly. 9 | * It may be stuck in a hole in the lawn, or under a obstacle, or there may be some other hardware issues, in either way it require some kind of human intervention. 10 | * This is a state that should not occur under normal conditions. 11 | */ 12 | class Stuck : public AbstractState { 13 | public: 14 | Stuck(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 15 | const char* const getStateName() { 16 | return "STUCK"; 17 | } 18 | void selected(Definitions::MOWER_STATES lastState); 19 | void process(); 20 | 21 | private: 22 | Definitions::MOWER_STATES previousState; 23 | unsigned long retryTimer = 0; // when did we last try if we are still stuck? 24 | }; 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /src/states/test.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "test.h" 3 | #include "state_controller.h" 4 | 5 | Test::Test(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources) : AbstractState(myState, stateController, resources), testSequence(true) { 6 | 7 | } 8 | 9 | void Test::selected(Definitions::MOWER_STATES lastState) { 10 | // clear previous scheduled sequence. 11 | testSequence.clear(); 12 | 13 | testSequence.schedule([this]() { 14 | Log.notice(F("cutter start" CR)); 15 | resources.cutter.start(); 16 | }, 4000); 17 | 18 | testSequence.schedule([this]() { 19 | Log.notice(F("forward" CR)); 20 | resources.wheelController.forward(0, 100, true); 21 | }, 2000); 22 | 23 | testSequence.schedule([this]() { 24 | Log.notice(F("stop" CR)); 25 | resources.wheelController.stop(true); 26 | }, 20000); 27 | 28 | testSequence.schedule([this]() { 29 | Log.notice(F("left" CR)); 30 | resources.wheelController.turn(-90); 31 | }, 50); 32 | 33 | testSequence.schedule([this]() { 34 | Log.notice(F("right" CR)); 35 | resources.wheelController.turn(90); 36 | }, 2000); 37 | 38 | testSequence.schedule([this]() { 39 | Log.notice(F("stop" CR)); 40 | resources.wheelController.stop(); 41 | }, 2000); 42 | 43 | testSequence.schedule([this]() { 44 | Log.notice(F("backward" CR)); 45 | resources.wheelController.backward(0, 100, true); 46 | }, 50); 47 | 48 | testSequence.schedule([this]() { 49 | Log.notice(F("stop" CR)); 50 | resources.wheelController.stop(true); 51 | }, 10000); 52 | 53 | testSequence.schedule([this, lastState]() { 54 | Log.notice(F("cutter stop" CR)); 55 | resources.cutter.stop(true); 56 | 57 | stateController.setState(lastState); 58 | }, 2000); 59 | } 60 | 61 | void Test::process() { 62 | testSequence.process(); 63 | } 64 | -------------------------------------------------------------------------------- /src/states/test.h: -------------------------------------------------------------------------------- 1 | #ifndef _state_test_h 2 | #define _state_test_h 3 | 4 | #include "abstract_state.h" 5 | #include "resources.h" 6 | #include "../scheduler/scheduler.h" 7 | 8 | /** 9 | * State the mower enters when it is commanded to run the test program. 10 | * Usually this mean testing the wheel motors, the cutter motor, and stuff that shows the mowing is working properly. 11 | */ 12 | class Test : public AbstractState { 13 | public: 14 | Test(Definitions::MOWER_STATES myState, StateController& stateController, Resources& resources); 15 | const char* const getStateName() { 16 | return "TEST"; 17 | } 18 | void selected(Definitions::MOWER_STATES lastState); 19 | void process(); 20 | 21 | private: 22 | Scheduler testSequence; 23 | }; 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /src/utils.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "configuration.h" 3 | 4 | namespace Utils { 5 | /** 6 | * If ESP has synced its software clock with the NTP-servers, in other words can we get a correct time reading. 7 | */ 8 | bool isTimeAvailable = false; 9 | 10 | /** 11 | * Generate a XX character long key/password of ASCII characters 12 | * @param length length of key in characters 13 | */ 14 | String generateKey(uint8_t length) { 15 | const String CHARS = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz"; 16 | String key = ""; 17 | // get true random number from the hardware RNG. this must be called after WiFi has been enabled to be truly random. 18 | for (int i = 0; i < length; i++) { 19 | key += CHARS[random(0, CHARS.length())]; 20 | } 21 | 22 | return key; 23 | } 24 | 25 | /** 26 | * Convert uint64_t to an String 27 | */ 28 | String uint64String(uint64_t value, unsigned char base) 29 | { 30 | char buf[1 + 8 * sizeof(uint64_t)]; 31 | ultoa(value, buf, base); 32 | return String(buf); 33 | } 34 | 35 | /** 36 | * Gets seconds since Unix epoctime (1970-01-01) 37 | */ 38 | int64_t getEpocTime() { 39 | struct timeval tv; 40 | gettimeofday(&tv, NULL); 41 | return (tv.tv_sec * 1000LL + (tv.tv_usec / 1000LL)); 42 | } 43 | 44 | /** 45 | * Get current date/time as a string 46 | * @param format e.g. "%d %b %Y, %H:%M:%S%z" 47 | * @param timeout for how many milliseconds we try to obtain time 48 | */ 49 | String getTime(String format, uint32_t timeout) { 50 | struct tm timeinfo; 51 | 52 | if (!getLocalTime(&timeinfo, timeout)) { 53 | isTimeAvailable = false; 54 | return F("Failed to obtain time"); 55 | } 56 | 57 | isTimeAvailable = true; 58 | 59 | char outstr[80]; 60 | strftime(outstr, sizeof(outstr), format.c_str(), &timeinfo); // ISO 8601 time 61 | 62 | return String(outstr); 63 | } 64 | } -------------------------------------------------------------------------------- /src/utils.h: -------------------------------------------------------------------------------- 1 | #ifndef _utils_h 2 | #define _utils_h 3 | 4 | #include 5 | #include 6 | 7 | 8 | /** 9 | * Assorted utility functions. 10 | */ 11 | namespace Utils { 12 | 13 | extern bool isTimeAvailable; 14 | 15 | extern String generateKey(uint8_t length); 16 | extern String uint64String(uint64_t value, uint8_t base = 10); 17 | extern int64_t getEpocTime(); 18 | extern String getTime(String format = "%d %b %Y, %H:%M:%S%z", uint32_t timeout = 5000); 19 | 20 | template 21 | extern T calculateMedian(std::vector entries); 22 | template 23 | extern T calculateMedian(T(&entries)[size]); 24 | 25 | /** 26 | * Get median value from an list of values 27 | */ 28 | template 29 | T calculateMedian(std::vector entries) { 30 | auto size = entries.size(); 31 | 32 | if (size == 0) { 33 | return 0; // Undefined, really. 34 | } else { 35 | sort(entries.begin(), entries.end()); 36 | 37 | if (size % 2 == 0) { 38 | return (entries[size / 2 - 1] + entries[size / 2]) / 2; 39 | } else { 40 | return entries[size / 2]; 41 | } 42 | } 43 | } 44 | 45 | /** 46 | * Get median value from an array of values 47 | */ 48 | template 49 | T calculateMedian(T(&entries)[size]) { 50 | 51 | if (size == 0) { 52 | return 0; // Undefined, really. 53 | } else { 54 | std::sort(&entries[0], entries + size); 55 | 56 | if (size % 2 == 0) { 57 | return (entries[size / 2 - 1] + entries[size / 2]) / 2; 58 | } else { 59 | return entries[size / 2]; 60 | } 61 | } 62 | } 63 | } 64 | 65 | #endif -------------------------------------------------------------------------------- /src/vector.h: -------------------------------------------------------------------------------- 1 | /* 2 | Inertial Measurement Unit Maths Library 3 | Copyright (C) 2013-2014 Samuel Cowen 4 | www.camelsoftware.com 5 | 6 | Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) 7 | 8 | This program is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | This program is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with this program. If not, see . 20 | */ 21 | 22 | #ifndef IMUMATH_VECTOR_HPP 23 | #define IMUMATH_VECTOR_HPP 24 | 25 | #include 26 | #include 27 | #include 28 | 29 | 30 | namespace imu 31 | { 32 | 33 | template class Vector 34 | { 35 | public: 36 | Vector() 37 | { 38 | memset(p_vec, 0, sizeof(double)*N); 39 | } 40 | 41 | Vector(double a) 42 | { 43 | memset(p_vec, 0, sizeof(double)*N); 44 | p_vec[0] = a; 45 | } 46 | 47 | Vector(double a, double b) 48 | { 49 | memset(p_vec, 0, sizeof(double)*N); 50 | p_vec[0] = a; 51 | p_vec[1] = b; 52 | } 53 | 54 | Vector(double a, double b, double c) 55 | { 56 | memset(p_vec, 0, sizeof(double)*N); 57 | p_vec[0] = a; 58 | p_vec[1] = b; 59 | p_vec[2] = c; 60 | } 61 | 62 | Vector(double a, double b, double c, double d) 63 | { 64 | memset(p_vec, 0, sizeof(double)*N); 65 | p_vec[0] = a; 66 | p_vec[1] = b; 67 | p_vec[2] = c; 68 | p_vec[3] = d; 69 | } 70 | 71 | Vector(const Vector &v) 72 | { 73 | for (int x = 0; x < N; x++) 74 | p_vec[x] = v.p_vec[x]; 75 | } 76 | 77 | ~Vector() 78 | { 79 | } 80 | 81 | uint8_t n() { return N; } 82 | 83 | double magnitude() const 84 | { 85 | double res = 0; 86 | for (int i = 0; i < N; i++) 87 | res += p_vec[i] * p_vec[i]; 88 | 89 | return sqrt(res); 90 | } 91 | 92 | void normalize() 93 | { 94 | double mag = magnitude(); 95 | if (isnan(mag) || mag == 0.0) 96 | return; 97 | 98 | for (int i = 0; i < N; i++) 99 | p_vec[i] /= mag; 100 | } 101 | 102 | double dot(const Vector& v) const 103 | { 104 | double ret = 0; 105 | for (int i = 0; i < N; i++) 106 | ret += p_vec[i] * v.p_vec[i]; 107 | 108 | return ret; 109 | } 110 | 111 | // The cross product is only valid for vectors with 3 dimensions, 112 | // with the exception of higher dimensional stuff that is beyond 113 | // the intended scope of this library. 114 | // Only a definition for N==3 is given below this class, using 115 | // cross() with another value for N will result in a link error. 116 | Vector cross(const Vector& v) const; 117 | 118 | Vector scale(double scalar) const 119 | { 120 | Vector ret; 121 | for(int i = 0; i < N; i++) 122 | ret.p_vec[i] = p_vec[i] * scalar; 123 | return ret; 124 | } 125 | 126 | Vector invert() const 127 | { 128 | Vector ret; 129 | for(int i = 0; i < N; i++) 130 | ret.p_vec[i] = -p_vec[i]; 131 | return ret; 132 | } 133 | 134 | Vector& operator=(const Vector& v) 135 | { 136 | for (int x = 0; x < N; x++ ) 137 | p_vec[x] = v.p_vec[x]; 138 | return *this; 139 | } 140 | 141 | double& operator [](int n) 142 | { 143 | return p_vec[n]; 144 | } 145 | 146 | double operator [](int n) const 147 | { 148 | return p_vec[n]; 149 | } 150 | 151 | double& operator ()(int n) 152 | { 153 | return p_vec[n]; 154 | } 155 | 156 | double operator ()(int n) const 157 | { 158 | return p_vec[n]; 159 | } 160 | 161 | Vector operator+(const Vector& v) const 162 | { 163 | Vector ret; 164 | for(int i = 0; i < N; i++) 165 | ret.p_vec[i] = p_vec[i] + v.p_vec[i]; 166 | return ret; 167 | } 168 | 169 | Vector operator-(const Vector& v) const 170 | { 171 | Vector ret; 172 | for(int i = 0; i < N; i++) 173 | ret.p_vec[i] = p_vec[i] - v.p_vec[i]; 174 | return ret; 175 | } 176 | 177 | Vector operator * (double scalar) const 178 | { 179 | return scale(scalar); 180 | } 181 | 182 | Vector operator / (double scalar) const 183 | { 184 | Vector ret; 185 | for(int i = 0; i < N; i++) 186 | ret.p_vec[i] = p_vec[i] / scalar; 187 | return ret; 188 | } 189 | 190 | void toDegrees() 191 | { 192 | for(int i = 0; i < N; i++) 193 | p_vec[i] *= 57.2957795131; //180/pi 194 | } 195 | 196 | void toRadians() 197 | { 198 | for(int i = 0; i < N; i++) 199 | p_vec[i] *= 0.01745329251; //pi/180 200 | } 201 | 202 | double& x() { return p_vec[0]; } 203 | double& y() { return p_vec[1]; } 204 | double& z() { return p_vec[2]; } 205 | double x() const { return p_vec[0]; } 206 | double y() const { return p_vec[1]; } 207 | double z() const { return p_vec[2]; } 208 | 209 | 210 | private: 211 | double p_vec[N]; 212 | }; 213 | 214 | 215 | template <> 216 | inline Vector<3> Vector<3>::cross(const Vector& v) const 217 | { 218 | return Vector( 219 | p_vec[1] * v.p_vec[2] - p_vec[2] * v.p_vec[1], 220 | p_vec[2] * v.p_vec[0] - p_vec[0] * v.p_vec[2], 221 | p_vec[0] * v.p_vec[1] - p_vec[1] * v.p_vec[0] 222 | ); 223 | } 224 | 225 | } // namespace 226 | 227 | #endif -------------------------------------------------------------------------------- /src/wheel.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "wheel.h" 4 | #include "definitions.h" 5 | 6 | Wheel::Wheel(uint8_t wheel_id, uint8_t motor_pin, uint8_t motor_dir_pin, uint8_t odometer_pin, bool wheel_invert, uint8_t wheel_max_speed) : wheel_id(wheel_id), motor_pin(motor_pin), motor_dir_pin(motor_dir_pin), odometer_pin(odometer_pin), wheel_invert(wheel_invert), max_speed(constrain(wheel_max_speed, 0, 100)) { 7 | pinMode(motor_pin, OUTPUT); 8 | pinMode(motor_dir_pin, OUTPUT); 9 | pinMode(odometer_pin, INPUT_PULLUP); 10 | ledcSetup(wheel_id, Definitions::MOTOR_BASE_FREQ, Definitions::MOTOR_TIMER_13_BIT); 11 | ledcAttachPin(motor_pin, wheel_id); 12 | attachInterrupt(digitalPinToInterrupt(odometer_pin), std::bind(&Wheel::updateOdometer, this), RISING); 13 | 14 | setSpeed(0); 15 | } 16 | 17 | Wheel::~Wheel() { 18 | setSpeed(0); 19 | detachInterrupt(digitalPinToInterrupt(odometer_pin)); 20 | } 21 | 22 | void Wheel::setSpeed(int8_t speed) { 23 | speed = constrain(speed, -max_speed, max_speed); 24 | current_speed = speed; 25 | 26 | // if speed is negative then reverse motor direction. 27 | if (speed < 0) { 28 | digitalWrite(motor_dir_pin, wheel_invert ? 1 : 0); 29 | } else { 30 | digitalWrite(motor_dir_pin, wheel_invert ? 0 : 1); 31 | } 32 | // calculate duty, 8191 from 2 ^ 13 - 1 33 | uint32_t duty = ((pow(2, Definitions::MOTOR_TIMER_13_BIT) - 1) / 100) * abs(speed); 34 | // write duty to motor using wheel_id as channel 35 | ledcWrite(wheel_id, duty); 36 | } 37 | 38 | int8_t Wheel::getSpeed() { 39 | return current_speed; 40 | } 41 | 42 | void IRAM_ATTR Wheel::updateOdometer() { 43 | portENTER_CRITICAL_ISR(&mux); 44 | odometer++; 45 | portEXIT_CRITICAL_ISR(&mux); 46 | } 47 | 48 | uint32_t Wheel::getOdometer() { 49 | return odometer; 50 | } -------------------------------------------------------------------------------- /src/wheel.h: -------------------------------------------------------------------------------- 1 | #ifndef _wheel_h 2 | #define _wheel_h 3 | 4 | #include 5 | 6 | class Wheel { 7 | public: 8 | Wheel(uint8_t wheel_id, uint8_t motor_pin, uint8_t motor_dir_pin, uint8_t odometer_pin, bool wheel_invert, uint8_t wheel_max_speed); 9 | ~Wheel(); 10 | /** 11 | * Set motor speed, 0->100% to drive forward, -100->0% to drive backward. 12 | * @param speed speed in percent from -100 -> 100. 13 | */ 14 | void setSpeed(int8_t speed); 15 | int8_t getSpeed(); 16 | uint32_t getOdometer(); 17 | 18 | private: 19 | uint8_t wheel_id; 20 | uint8_t motor_pin; 21 | uint8_t motor_dir_pin; 22 | uint8_t odometer_pin; 23 | bool wheel_invert; 24 | uint8_t max_speed; 25 | int8_t current_speed = 0; 26 | portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED; 27 | volatile uint32_t odometer = 0; 28 | void IRAM_ATTR updateOdometer(); 29 | }; 30 | 31 | #endif 32 | -------------------------------------------------------------------------------- /src/wheel_controller.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "wheel_controller.h" 3 | 4 | static const float PULSE_PER_CENTIMETER = Definitions::WHEEL_ODOMETERPULSES_PER_ROTATION / (Definitions::WHEEL_DIAMETER * PI / 10); 5 | static const float PULSE_PER_DEGREE = (((Definitions::WHEEL_PAIR_DISTANCE * PI) / (Definitions::WHEEL_DIAMETER * PI / 10)) * Definitions::WHEEL_ODOMETERPULSES_PER_ROTATION) / 360; 6 | 7 | WheelController::WheelController(Wheel& leftWheel, Wheel& rightWheel) : 8 | leftWheel(leftWheel), 9 | rightWheel(rightWheel) { } 10 | 11 | WheelController::~WheelController() { 12 | stop(false); 13 | } 14 | 15 | void WheelController::forward(int8_t turnrate, uint8_t speed, bool smooth, uint32_t distance, const TargetReachedCallback& fn) { 16 | turnrate = constrain(turnrate, -100, 100); 17 | speed = constrain(speed, 0, 100); 18 | lastSpeed = 0; 19 | 20 | if (speed > 0 && speed < Definitions::WHEEL_MOTOR_MIN_SPEED) { 21 | speed = Definitions::WHEEL_MOTOR_MIN_SPEED; 22 | } 23 | 24 | if (distance > 0) { 25 | auto currentOdometer = leftWheel.getOdometer(); // we only need to count on one wheel, since they always the same distance (but maybe in the opposite direction) 26 | targetOdometer = currentOdometer + distance * PULSE_PER_CENTIMETER; 27 | reachedTargetCallback = fn; 28 | } else { 29 | targetOdometer = 0; 30 | } 31 | 32 | Log.trace(F("WheelController-forward, speed: %d, turnrate: %d, smooth: %d, distance: %d" CR), speed, turnrate, smooth, distance); 33 | 34 | if (turnrate < 0) { 35 | leftWheel.setSpeed(speed * (100 + turnrate) / 100); 36 | rightWheel.setSpeed(speed); 37 | } else if (turnrate > 0) { 38 | leftWheel.setSpeed(speed); 39 | rightWheel.setSpeed(speed * (100 - turnrate) / 100); 40 | } else { 41 | leftWheel.setSpeed(speed); 42 | rightWheel.setSpeed(speed); 43 | } 44 | } 45 | 46 | void WheelController::backward(int8_t turnrate, uint8_t speed, bool smooth, uint32_t distance, const TargetReachedCallback& fn) { 47 | turnrate = constrain(turnrate, -100, 100); 48 | speed = constrain(speed, 0, 100); 49 | lastSpeed = 0; 50 | 51 | if (speed > 0 && speed < Definitions::WHEEL_MOTOR_MIN_SPEED) { 52 | speed = Definitions::WHEEL_MOTOR_MIN_SPEED; 53 | } 54 | 55 | if (distance > 0) { 56 | auto currentOdometer = leftWheel.getOdometer(); // we only need to count on one wheel, since they always the same distance (but maybe in the opposite direction) 57 | targetOdometer = currentOdometer + distance * PULSE_PER_CENTIMETER; 58 | reachedTargetCallback = fn; 59 | } else { 60 | targetOdometer = 0; 61 | } 62 | 63 | Log.trace(F("WheelController-backward, speed: %d, turnrate: %d, smooth: %d, distance: %d" CR), speed, turnrate, smooth, distance); 64 | 65 | if (turnrate < 0) { 66 | leftWheel.setSpeed(-speed * (100 + turnrate) / 100); 67 | rightWheel.setSpeed(-speed); 68 | } else if (turnrate > 0) { 69 | leftWheel.setSpeed(-speed); 70 | rightWheel.setSpeed(-speed * (100 + turnrate) / 100); 71 | } else { 72 | leftWheel.setSpeed(-speed); 73 | rightWheel.setSpeed(-speed); 74 | } 75 | } 76 | 77 | void WheelController::turn(int16_t direction, const TargetReachedCallback& fn) { 78 | direction = constrain(direction, -360, 360); 79 | reachedTargetCallback = fn; 80 | lastSpeed = leftWheel.getSpeed(); // save current speed so that we can return to this after turn. 81 | 82 | auto currentOdometer = leftWheel.getOdometer(); // we only need to count on one wheel, since they always the same distance (but maybe in the opposite direction) 83 | targetOdometer = currentOdometer + abs(direction) * PULSE_PER_DEGREE; 84 | 85 | Log.trace(F("WheelController-turn, direction: %i, currentOdometer: %i, targetOdometer: %i" CR), direction, currentOdometer, targetOdometer); 86 | 87 | if (direction < 0) { 88 | leftWheel.setSpeed(-Definitions::WHEEL_MOTOR_TURN_SPEED); 89 | rightWheel.setSpeed(Definitions::WHEEL_MOTOR_TURN_SPEED); 90 | } else if (direction > 0) { 91 | leftWheel.setSpeed(Definitions::WHEEL_MOTOR_TURN_SPEED); 92 | rightWheel.setSpeed(-Definitions::WHEEL_MOTOR_TURN_SPEED); 93 | } 94 | } 95 | 96 | void WheelController::stop(bool smooth) { 97 | leftWheel.setSpeed(0); 98 | rightWheel.setSpeed(0); 99 | targetOdometer = 0; 100 | reachedTargetCallback = nullptr; 101 | lastSpeed = 0; 102 | 103 | Log.trace(F("WheelController-stop, smooth: %d" CR), smooth); 104 | } 105 | 106 | status WheelController::getStatus() { 107 | return { 108 | leftWheel.getSpeed(), 109 | rightWheel.getSpeed() 110 | }; 111 | } 112 | 113 | bool WheelController::increaseForwardSpeed() { 114 | auto leftSpeed = leftWheel.getSpeed(); 115 | auto rightSpeed = rightWheel.getSpeed(); 116 | 117 | if (leftSpeed == rightSpeed && leftSpeed > 0 && leftSpeed < 100) { 118 | leftWheel.setSpeed(leftSpeed + 10); 119 | rightWheel.setSpeed(rightSpeed + 10); 120 | 121 | return true; 122 | } 123 | 124 | return false; 125 | } 126 | 127 | bool WheelController::decreaseForwardSpeed() { 128 | auto leftSpeed = leftWheel.getSpeed(); 129 | auto rightSpeed = rightWheel.getSpeed(); 130 | 131 | if (leftSpeed == rightSpeed && leftSpeed >= 20) { 132 | leftWheel.setSpeed(leftSpeed - 10); 133 | rightWheel.setSpeed(rightSpeed - 10); 134 | 135 | return true; 136 | } 137 | 138 | return false; 139 | } 140 | 141 | void WheelController::process() { 142 | // TODO: handle smooth-running. 143 | 144 | // check if we have reached target 145 | if (targetOdometer > 0 && leftWheel.getOdometer() >= targetOdometer) { 146 | targetOdometer = 0; 147 | Log.trace(F("WheelController-process, reached target" CR)); 148 | 149 | leftWheel.setSpeed(lastSpeed); 150 | rightWheel.setSpeed(lastSpeed); 151 | 152 | if (reachedTargetCallback != nullptr) { 153 | reachedTargetCallback(); 154 | reachedTargetCallback = nullptr; 155 | } 156 | } 157 | } 158 | -------------------------------------------------------------------------------- /src/wheel_controller.h: -------------------------------------------------------------------------------- 1 | #ifndef _wheel_controller_h 2 | #define _wheel_controller_h 3 | 4 | #include 5 | #include 6 | #include "wheel.h" 7 | #include "definitions.h" 8 | #include "processable.h" 9 | 10 | struct status { 11 | int16_t leftWheelSpeed; 12 | int16_t rightWheelSpeed; 13 | }; 14 | 15 | class WheelController : public Processable { 16 | public: 17 | typedef std::function TargetReachedCallback; 18 | 19 | WheelController(Wheel& leftWheel, Wheel& rightWheel); 20 | ~WheelController(); 21 | /** 22 | * Drives mower forward at specified speed and turning at specified speed. 23 | * @param turnrate speed of turning (-1 to -100 left, 1 to 100 right). 0 = don't turn. 24 | * @param speed forward speed (0-100%) 25 | * @param smooth smoothly take us to target speed. 26 | * @param distance [optional] distance we want mower to move (in centimeters). 27 | * @param fn [optional] callback that will be executed once mower has moved desired distance. 28 | */ 29 | void forward(int8_t turnrate, uint8_t speed, bool smooth = false, uint32_t distance = 0, const TargetReachedCallback& fn = nullptr); 30 | /** 31 | * Drives mower backward at specified speed and turning at specified speed. 32 | * @param turnrate speed of turning (-1 to -100 left, 1 to 100 right). 0 = don't turn. 33 | * @param speed backward speed (0-100%) 34 | * @param smooth smoothly take us to target speed. 35 | * @param distance [optional] distance we want mower to move (in centimeters). 36 | * @param fn [optional] callback that will be executed once mower has moved desired distance. 37 | */ 38 | void backward(int8_t turnrate, uint8_t speed, bool smooth = false, uint32_t distance = 0, const TargetReachedCallback& fn = nullptr); 39 | /** 40 | * Turns mower on the spot. 41 | * @param direction turns mower to the specified direction. Direction is -360 -> 360 degrees relative current heading. 42 | * @param fn [optional] callback that will be executed once mower is facing desired direction. 43 | */ 44 | void turn(int16_t direction, const TargetReachedCallback& fn = nullptr); 45 | /** 46 | * Stop mowers movement. 47 | * @param smooth smoothly take us to halt. 48 | */ 49 | void stop(bool smooth = false); 50 | 51 | /** 52 | * Return current speed for all wheels 53 | * @return wheels status 54 | */ 55 | status getStatus(); 56 | 57 | /** 58 | * If mower is currently driving forward then this method will try to increase the speed of the wheels even more. 59 | * @return if increase could be made 60 | */ 61 | bool increaseForwardSpeed(); 62 | 63 | /** 64 | * If mower is currently driving forward then this method will try to decrease the speed of the wheels, it will however never stop completely. 65 | * @return if decrease could be made 66 | */ 67 | bool decreaseForwardSpeed(); 68 | 69 | /* Internal use only! */ 70 | void process(); 71 | 72 | private: 73 | Wheel& leftWheel; 74 | Wheel& rightWheel; 75 | uint32_t targetOdometer = 0; 76 | int8_t targetSpeed = 0; 77 | int8_t lastSpeed = 0; 78 | TargetReachedCallback reachedTargetCallback; 79 | }; 80 | 81 | #endif 82 | -------------------------------------------------------------------------------- /web/.eslintignore: -------------------------------------------------------------------------------- 1 | node_modules/ 2 | -------------------------------------------------------------------------------- /web/.eslintrc: -------------------------------------------------------------------------------- 1 | { 2 | "rules": { 3 | "indent": [ 4 | 2, 5 | 2, 6 | {"VariableDeclarator": { "var": 2, "let": 2, "const": 3}} 7 | ], 8 | "linebreak-style": [2, "unix"], 9 | "semi": [2, "always"], 10 | "comma-dangle": [2, "always-multiline"], 11 | "no-console": "off" 12 | }, 13 | "env": { 14 | "es6": true, 15 | "browser": true 16 | }, 17 | "extends": [ 18 | "eslint:recommended", 19 | "plugin:import/errors", 20 | "plugin:import/warnings" 21 | ], 22 | "parserOptions": { 23 | "ecmaFeatures": { 24 | "experimentalObjectRestSpread": true, 25 | "ecmaVersion": 6, 26 | "sourceType": "module" 27 | } 28 | }, 29 | "globals": { 30 | "require": false, 31 | "module": true, 32 | "Environment": false, 33 | "__dirname": false, 34 | "process": false 35 | } 36 | } 37 | -------------------------------------------------------------------------------- /web/.stylelintrc: -------------------------------------------------------------------------------- 1 | { 2 | "rules": { 3 | "block-no-empty": null, 4 | "color-no-invalid-hex": true, 5 | "comment-empty-line-before": [ "always", { 6 | "ignore": ["stylelint-commands", "after-comment"] 7 | } ], 8 | "declaration-colon-space-after": "always", 9 | "max-empty-lines": 2, 10 | "rule-empty-line-before": [ "always", { 11 | "except": ["first-nested"], 12 | "ignore": ["after-comment"] 13 | } ], 14 | "unit-whitelist": ["vw", "px", "em", "rem", "%", "s", "ms"] 15 | } 16 | } -------------------------------------------------------------------------------- /web/build/webpack.config.js: -------------------------------------------------------------------------------- 1 | 2 | // Define this constant for easier usage 3 | const isProd = process.env.NODE_ENV === 'production'; 4 | const { resolve } = require('path'); 5 | const webpack = require('webpack'); 6 | const HtmlWebpackPlugin = require('html-webpack-plugin'); 7 | const ExtractTextPlugin = require('extract-text-webpack-plugin'); 8 | const CopyWebpackPlugin = require('copy-webpack-plugin'); 9 | const apiMocker = require('mocker-api'); 10 | const CleanWebpackPlugin = require('clean-webpack-plugin'); 11 | const CompressionPlugin = require('compression-webpack-plugin'); 12 | const StyleLintPlugin = require('stylelint-webpack-plugin'); 13 | // eslint-disable-next-line no-unused-vars 14 | const myIp = require('my-local-ip'); 15 | 16 | const config = { 17 | 18 | mode: isProd ? 'production' : 'development', 19 | 20 | entry: { 21 | // Main entry point of our app 22 | app: resolve(__dirname, '..', 'src', 'index.js'), 23 | }, 24 | 25 | output: { 26 | // built files are stored in "data"-directory in the root of the project. 27 | path: resolve(__dirname, '..', '..', 'data'), 28 | 29 | // In our case we serve assets directly from root 30 | publicPath: '/', 31 | 32 | // We add hash to filename to avoid caching issues 33 | filename: '[hash].js', 34 | //filename: '[name].[hash].js', // can't use this because filename becomes too long, max limit of 32 chars in SPIFFS. 35 | }, 36 | 37 | resolve: { 38 | extensions: ['*', '.js'], 39 | modules: [ 40 | resolve(__dirname, '..', 'node_modules'), 41 | ], 42 | }, 43 | 44 | module: { 45 | rules: [ 46 | { 47 | test: /\.js$/, 48 | exclude: /node_modules/, 49 | use: { 50 | loader: 'babel-loader', 51 | options: { 52 | presets: [ 53 | ["@babel/preset-env", 54 | { 55 | "targets": ">5%", 56 | "debug": true, 57 | }, 58 | ], 59 | ], 60 | }, 61 | }, 62 | }, 63 | { 64 | test: /\.css$/, 65 | use: ExtractTextPlugin.extract({ 66 | fallback: 'style-loader', 67 | use: 'css-loader', 68 | }), 69 | }, 70 | { 71 | test: /\.scss|\.sass$/, 72 | use: ExtractTextPlugin.extract({ 73 | fallback: 'style-loader', 74 | use: ['css-loader', 'sass-loader'], 75 | }), 76 | }, 77 | { 78 | test: /\.(png|jpe?g|gif|svg)(\?.*)?$/, 79 | loader: 'url-loader', 80 | query: { 81 | limit: 10000, 82 | name: 'images/[name].[hash:7].[ext]', 83 | }, 84 | }, 85 | { 86 | test: /\.(woff2?|eot|ttf|otf)(\?.*)?$/, 87 | loader: 'url-loader', 88 | options: { 89 | limit: 1000, 90 | name: 'fonts/[name].[hash:7].[ext]', 91 | }, 92 | }, 93 | ], 94 | }, 95 | 96 | plugins: [ 97 | new CleanWebpackPlugin(resolve(__dirname, '..', '..', 'data'), { 98 | allowExternal: true, 99 | }), 100 | new HtmlWebpackPlugin({ 101 | template: resolve(__dirname, '..', 'src', 'html', 'index.ejs'), 102 | }), 103 | new ExtractTextPlugin({ 104 | filename: '[hash].css', 105 | disable: !isProd, 106 | }), 107 | new webpack.optimize.ModuleConcatenationPlugin(), // Scope Hoisting: https://www.codementor.io/drewpowers/high-performance-webpack-config-for-front-end-delivery-90sqic1qa#1-scope-hoisting 108 | new webpack.optimize.LimitChunkCountPlugin({ 109 | maxChunks: 1, 110 | }), 111 | new CopyWebpackPlugin([ 112 | { 113 | from: resolve(__dirname, '..', 'src', 'html', 'swagger'), 114 | to: resolve(__dirname, '..', '..', 'data'), 115 | }, 116 | { 117 | from: resolve(__dirname, '..', 'src', 'favicons'), 118 | to: resolve(__dirname, '..', '..', 'data'), 119 | }, 120 | ]), 121 | new CompressionPlugin({ 122 | test: /(\.html|\.js|\.css|\.yaml)$/i, 123 | algorithm: 'gzip', 124 | threshold: 4096, // Only assets bigger than this size are processed. In bytes. 125 | compressionOptions: { level: 9 }, 126 | deleteOriginalAssets: isProd, 127 | }), 128 | new StyleLintPlugin({ 129 | configFile: resolve(__dirname, '..', '.stylelintrc'), 130 | context: resolve(__dirname, '..', 'src', 'styles'), 131 | }), 132 | ], 133 | }; 134 | 135 | if (!isProd) { 136 | config.devServer = { 137 | contentBase: resolve(__dirname, '..', 'static'), 138 | hot: true, 139 | publicPath: '/', 140 | historyApiFallback: true, 141 | proxy: { 142 | '/ws': { 143 | target: `ws://localhost:8081/websocket`, 144 | pathRewrite: {'^/ws' : ''}, 145 | ws: true, 146 | secure: false, 147 | logLevel: 'debug', 148 | }, 149 | }, 150 | before(app) { 151 | // load common mock data 152 | app.locals.mock = require(resolve(__dirname, '..', 'mock', 'mock-data.js')); 153 | // setup REST endpoints with mocked data, mock will be available in api-handlers on app.locals.mock. 154 | apiMocker(app, resolve(__dirname, '..', 'mock', 'api-mocker.js')); 155 | // setup Websocket with mocked data 156 | require(resolve(__dirname, '..', 'mock', 'socket-mocker.js'))(8081, app.locals.mock); 157 | }, 158 | }; 159 | } else { 160 | // Add buildcheck if any resources grow too big, the embeded system has very limited space. 161 | config.performance = { 162 | hints: 'warning', 163 | maxEntrypointSize: 50000, 164 | maxAssetSize: 60000, 165 | }; 166 | } 167 | 168 | module.exports = config; 169 | -------------------------------------------------------------------------------- /web/liam-esp@1.0.0: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/liam-esp@1.0.0 -------------------------------------------------------------------------------- /web/mock/api-mocker.js: -------------------------------------------------------------------------------- 1 | /** 2 | * Liam-ESP emulator 3 | * Simple application using [mocker-api](https://www.npmjs.com/package/mocker-api) to emulate a Liam-ESP lawnmover and answering the same REST request the mower normally does. 4 | * This is useful when you want to develop the GUI without having a lawn mover at hand (or risking starting the cutter and chopping of your hands). 5 | * 6 | * Start emulator: 7 | * 1. install Node.js (https://nodejs.org) 8 | * 2. "npm install" (installs all dependencies) 9 | * 3. "npm run dev" (start emulator) 10 | * 4. point webbrowser to "http://localhost:8080" 11 | */ 12 | 13 | const Cookies = require('cookies'); 14 | 15 | function isAuthenticated(req, res) { 16 | let cookies = new Cookies(req, res); 17 | let sessionVal = cookies.get(`liam-${req.app.locals.mock.getCurrentSystem().mowerId}`); 18 | return sessionVal === '1234567'; 19 | } 20 | 21 | let proxy = { 22 | 'GET /api/v1/status': (req, res) => { 23 | if (isAuthenticated(req, res)) { 24 | return res.json(req.app.locals.mock.getCurrentState()); 25 | } else { 26 | res.sendStatus(401); 27 | } 28 | }, 29 | 'PUT /api/v1/state': (req, res) => { 30 | if (isAuthenticated(req, res)) { 31 | req.app.locals.mock.setState(req.body.state); 32 | res.sendStatus(200); 33 | } else { 34 | res.sendStatus(401); 35 | } 36 | }, 37 | 'PUT /api/v1/manual/cutter_on': (req, res) => { 38 | if (isAuthenticated(req, res)) { 39 | req.app.locals.mock.cutterOn(); 40 | res.sendStatus(200); 41 | } else { 42 | res.sendStatus(401); 43 | } 44 | }, 45 | 'PUT /api/v1/manual/cutter_off': (req, res) => { 46 | if (isAuthenticated(req, res)) { 47 | req.app.locals.mock.cutterOff(); 48 | res.sendStatus(200); 49 | } else { 50 | res.sendStatus(401); 51 | } 52 | }, 53 | 'PUT /api/v1/manual/forward': (req, res) => { 54 | if (isAuthenticated(req, res)) { 55 | //TODO 56 | res.sendStatus(200); 57 | } else { 58 | res.sendStatus(401); 59 | } 60 | }, 61 | 'PUT /api/v1/manual/backward': (req, res) => { 62 | if (isAuthenticated(req, res)) { 63 | //TODO 64 | res.sendStatus(200); 65 | } else { 66 | res.sendStatus(401); 67 | } 68 | }, 69 | 'PUT /api/v1/manual/turn': (req, res) => { 70 | if (isAuthenticated(req, res)) { 71 | //TODO 72 | res.sendStatus(200); 73 | } else { 74 | res.sendStatus(401); 75 | } 76 | }, 77 | 'PUT /api/v1/manual/stop': (req, res) => { 78 | if (isAuthenticated(req, res)) { 79 | req.app.locals.mock.stop(); 80 | res.sendStatus(200); 81 | } else { 82 | res.sendStatus(401); 83 | } 84 | }, 85 | 'GET /api/v1/history/battery': (req, res) => { 86 | if (isAuthenticated(req, res)) { 87 | return res.json({ 88 | samples: req.app.locals.mock.getBatterySamples(), 89 | }); 90 | } else { 91 | res.sendStatus(401); 92 | } 93 | }, 94 | 'GET /api/v1/system' : (req, res) => { 95 | if (isAuthenticated(req, res)) { 96 | return res.json(req.app.locals.mock.getCurrentSystem()); 97 | } else { 98 | res.sendStatus(401); 99 | } 100 | }, 101 | 'PUT /api/v1/reboot': (req, res) => { 102 | if (isAuthenticated(req, res)) { 103 | res.sendStatus(200); 104 | } else { 105 | res.sendStatus(401); 106 | } 107 | }, 108 | 'PUT /api/v1/factoryreset': (req, res) => { 109 | if (isAuthenticated(req, res)) { 110 | res.sendStatus(200); 111 | } else { 112 | res.sendStatus(401); 113 | } 114 | }, 115 | 'GET /api/v1/loglevel': (req, res) => { 116 | if (isAuthenticated(req, res)) { 117 | return res.json(req.app.locals.mock.getLoglevel()); 118 | } else { 119 | res.sendStatus(401); 120 | } 121 | }, 122 | 'PUT /api/v1/loglevel': (req, res) => { 123 | if (isAuthenticated(req, res)) { 124 | req.app.locals.mock.setLoglevel(req.body.level); 125 | res.sendStatus(200); 126 | } else { 127 | res.sendStatus(401); 128 | } 129 | }, 130 | 'GET /api/v1/logmessages': (req, res) => { 131 | if (isAuthenticated(req, res)) { 132 | return res.json(req.app.locals.mock.getLogmessages(req.query.lastnr)); 133 | } else { 134 | res.sendStatus(401); 135 | } 136 | }, 137 | 'POST /api/v1/session': (req, res) => { 138 | let cookies = new Cookies(req, res); 139 | console.dir(req.body); 140 | if (req.body.username === 'admin' && req.body.password === 'liam') { 141 | cookies.set(`liam-${req.app.locals.mock.getCurrentSystem().mowerId}`, '1234567', { 142 | path: '/api', 143 | }); 144 | res.sendStatus(201); 145 | } else { 146 | res.sendStatus(401); 147 | } 148 | }, 149 | 'GET /api/v1/session': (req, res) => { 150 | if (isAuthenticated(req, res)) { 151 | res.sendStatus(200); 152 | } else { 153 | res.sendStatus(401); 154 | } 155 | }, 156 | 'DELETE /api/v1/session': (req, res) => { 157 | let cookies = new Cookies(req, res); 158 | cookies.set(`liam-${req.app.locals.mock.getCurrentSystem().mowerId}`, 'null', { 159 | path: '/api', 160 | maxAge: 0, 161 | }); 162 | res.sendStatus(200); 163 | }, 164 | 165 | 'POST /api/v1/apikey': (req, res) => { 166 | if (isAuthenticated(req, res)) { 167 | const CHARS = '0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz'; 168 | let key = 'xxxxxxxxxxxxxxxx'.replace(/[x]/g, function() { 169 | return CHARS[Math.floor(Math.random() * CHARS.length)]; 170 | }); 171 | 172 | req.app.locals.mock.setApiKey(key); 173 | res.sendStatus(201); 174 | } else { 175 | res.sendStatus(401); 176 | } 177 | }, 178 | 'POST /updatefirmware': (req, res) => { 179 | if (isAuthenticated(req, res)) { 180 | res.writeHead(303, {'Content-Type': 'text/plain', 'Location': '/'}); 181 | res.end('SUCCESS'); 182 | } else { 183 | res.sendStatus(401); 184 | } 185 | }, 186 | 'GET /api/v1/schedules': (req, res) => { 187 | if (isAuthenticated(req, res)) { 188 | return res.json(req.app.locals.mock.getSchedules()); 189 | } else { 190 | res.sendStatus(401); 191 | } 192 | }, 193 | 'POST /api/v1/schedules': (req, res) => { 194 | if (isAuthenticated(req, res)) { 195 | req.app.locals.mock.addScheduleEntry(req.body); 196 | res.sendStatus(201); 197 | } else { 198 | res.sendStatus(401); 199 | } 200 | }, 201 | 'DELETE /api/v1/schedules/:id': (req, res) => { 202 | if (isAuthenticated(req, res)) { 203 | req.app.locals.mock.removeScheduleEntry(req.params.id); 204 | res.sendStatus(200); 205 | } else { 206 | res.sendStatus(401); 207 | } 208 | }, 209 | }; 210 | 211 | module.exports = proxy; 212 | -------------------------------------------------------------------------------- /web/mock/mock-data.js: -------------------------------------------------------------------------------- 1 | const moveSequence = require('./moveSequence.json'), 2 | timeRegExp = /(00|01|02|03|04|05|06|07|08|09|10|11|12|13|14|15|16|17|18|19|20|21|22|23):(0|1|2|3|4|5)\d/g; 3 | 4 | let uptime = new Date(), 5 | loglevel = 4, 6 | seqPos = 0, 7 | currentState = { 8 | state: 'DOCKED', 9 | isCharging: false, 10 | cutterRotating: false, 11 | batteryVoltage: Math.floor(Math.random() * (16.8 - 14.0 + 1)) + 14.0, 12 | batteryLevel: Math.round(Math.random() * 100), 13 | batteryChargeCurrent: 0.0, 14 | lastFullyChargeTime: new Date() - 1000, 15 | lastChargeDuration: 1000 * 60 * 60, 16 | wifiSignal: Math.floor(Math.random() * (-30 - -90 + 1)) + -90, 17 | cutterLoad: Math.round(Math.random() * 100), 18 | uptime: uptime, 19 | leftWheelSpd: 0, 20 | rightWheelSpd: 0, 21 | pitch: 0, 22 | roll: 0, 23 | heading: 0, 24 | obstacles: { 25 | left: 0, 26 | front: 0, 27 | right: 0, 28 | }, 29 | }, 30 | currentSystem = { 31 | name: 'liam-esp', 32 | version: '1.0.0', 33 | mowerId: '413445680', 34 | totalHeap: 327420, 35 | freeHeap: Math.floor(Math.random() * 327420), 36 | minFreeHeap: 289640, 37 | getMaxAllocHeap: 113792, 38 | apiKey: '17ff5eEc39fD847B', 39 | localTime: '01 Nov 2018, 21:57:10+0100', 40 | settings: { 41 | batteryFullVoltage: 16.8, 42 | batteryEmptyVoltage: 14.0, 43 | }, 44 | }, 45 | schedules = []; 46 | 47 | module.exports = { 48 | getCurrentState: () => { 49 | let state = JSON.parse(JSON.stringify(currentState)); // deep copy, don't affect original. 50 | state.batteryVoltage = Math.floor(Math.random() * (16.8 - 14.0 + 1)) + 14.0; 51 | state.batteryLevel = Math.round(Math.random() * 100); 52 | state.batteryChargeCurrent = 0.0; 53 | 54 | state.cutterLoad = Math.round(Math.random() * 100); 55 | 56 | state.uptime = Math.round((new Date().getTime() - uptime.getTime()) / 1000); 57 | state.wifiSignal = Math.floor(Math.random() * (-30 - -90 + 1)) + -90; 58 | 59 | if (currentState.state === 'MOWING') { 60 | 61 | let currSequence = moveSequence[seqPos]; 62 | state.roll = currSequence.r || 0; 63 | state.pitch = currSequence.p || 0; 64 | state.heading = currSequence.h || 0; 65 | state.leftWheelSpd = currSequence.lw || 0; 66 | state.rightWheelSpd = currSequence.rw || currSequence.lw; 67 | 68 | } else if (currentState.state === 'TEST') { 69 | // random movement and rotation if TEST-state. 70 | state.roll = Math.floor(Math.random() * 90) - 45; 71 | state.pitch = Math.floor(Math.random() * 90) - 45; 72 | state.leftWheelSpd = Math.round(-100 + Math.random() * (100 - -100)); // -100 to 100 73 | state.rightWheelSpd = Math.round(-100 + Math.random() * (100 - -100)); // -100 to 100 74 | } 75 | 76 | return state; 77 | }, 78 | advanceSequence: () => { 79 | // only "animate" mowing during the mowing-state. 80 | if (currentState.state === 'MOWING') { 81 | seqPos = (seqPos + 1) % moveSequence.length; 82 | console.log(`movesequence: ${seqPos}`); 83 | } 84 | }, 85 | getCurrentSystem: () => { 86 | let system = JSON.parse(JSON.stringify(currentSystem)); // deep copy, don't affect original. 87 | 88 | return system; 89 | }, 90 | getBatterySamples: () => { 91 | let samples = { 92 | time: [], 93 | value: [], 94 | }, 95 | date = new Date().getTime(); 96 | 97 | for (let i = 0; i < 100; i++) { 98 | samples.time.push(date + i); 99 | samples.value.push(16.8 - i / 100); 100 | } 101 | 102 | return samples; 103 | }, 104 | cutterOn: () => { 105 | currentState.state = 'MANUAL'; 106 | currentState.cutterRotating = true; 107 | }, 108 | cutterOff: () => { 109 | currentState.state = 'MANUAL'; 110 | currentState.cutterRotating = false; 111 | }, 112 | forward: (speed, turnrate, smooth) => { 113 | currentState.state = 'MANUAL'; 114 | }, 115 | backward: (speed, turnrate, smooth) => { 116 | currentState.state = 'MANUAL'; 117 | }, 118 | stop: () => { 119 | currentState.state = 'MANUAL'; 120 | currentState.leftWheelSpd = 0; 121 | currentState.rightWheelSpd = 0; 122 | currentState.cutterRotating = false; 123 | 124 | }, 125 | setState: (state) => { 126 | currentState.state = state; 127 | 128 | switch (state) { 129 | case 'DOCKED': 130 | case 'CHARGING': 131 | case 'STUCK': 132 | case 'FLIPPED': 133 | case 'STOP': 134 | currentState.roll = 0; 135 | currentState.pitch = 0; 136 | currentState.leftWheelSpd = 0; 137 | currentState.rightWheelSpd = 0; 138 | currentState.cutterRotating = false; 139 | break; 140 | 141 | case 'LAUNCHING': 142 | currentState.roll = 0; 143 | currentState.pitch = 0; 144 | currentState.leftWheelSpd = -80; 145 | currentState.rightWheelSpd = -80; 146 | currentState.cutterRotating = false; 147 | 148 | setTimeout(() => { 149 | currentState.leftWheelSpd = -40; 150 | currentState.rightWheelSpd = 40; 151 | 152 | setTimeout(() => { 153 | currentState.state = 'MOWING'; 154 | currentState.leftWheelSpd = 80; 155 | currentState.rightWheelSpd = 80; 156 | currentState.cutterRotating = true; 157 | }, 3000); 158 | }, 4000); 159 | 160 | break; 161 | 162 | case 'DOCKING': 163 | currentState.roll = 0; 164 | currentState.pitch = 0; 165 | currentState.leftWheelSpd = 80; 166 | currentState.rightWheelSpd = 80; 167 | currentState.cutterRotating = false; 168 | 169 | setTimeout(() => { 170 | currentState.state = 'DOCKED'; 171 | currentState.leftWheelSpd = 0; 172 | currentState.rightWheelSpd = 0; 173 | }, 4000); 174 | 175 | break; 176 | 177 | case 'MOWING': 178 | currentState.cutterRotating = true; 179 | break; 180 | } 181 | }, 182 | getLoglevel: () => { 183 | return { 184 | level: loglevel, 185 | }; 186 | }, 187 | setLoglevel: (level) => { 188 | loglevel = level; 189 | }, 190 | getLogmessages: (lastnr) => { 191 | return { 192 | messages: lastnr == 8 ? [] : [ 193 | 'N: Gyro/accelerometer/compass init success.', 194 | 'N: New state: DOCKED', 195 | 'N: AP Started, AP SSID: "liam-esp", AP IPv4: 192.168.4.1', 196 | 'N: Web server initialized', 197 | 'N: using MQTT server IP: 192.168.1.10, and port: 1883', 198 | 'N: OTA available.', 199 | 'N: Connected to WiFi accesspoint "Stargate", using IP-address: 192.168.1.123 and MAC: 30:AE:A4:19:33:44', 200 | 'N: Connected to the MQTT broker.', 201 | ], 202 | lastnr: 8, 203 | total: 8, 204 | }; 205 | }, 206 | setApiKey: (key) => { 207 | currentSystem.apiKey = key; 208 | }, 209 | getSchedules: () => { 210 | return schedules; 211 | }, 212 | addScheduleEntry: (entry) => { 213 | if (entry.startTime.match(timeRegExp) && entry.stopTime.match(timeRegExp)) { 214 | schedules.unshift({ 215 | activeWeekdays: entry.activeWeekdays, 216 | startTime: entry.startTime, 217 | stopTime: entry.stopTime, 218 | }); 219 | } 220 | }, 221 | removeScheduleEntry: (position) => { 222 | schedules.splice(position, 1); 223 | }, 224 | }; 225 | -------------------------------------------------------------------------------- /web/mock/moveSequence.json: -------------------------------------------------------------------------------- 1 | [ 2 | { 3 | "lw": 50, 4 | "rw": 50, 5 | "p": 0, 6 | "r": 0, 7 | "h": 1, 8 | "lat": "57.557295566492456", 9 | "lng": "18.525826235938553" 10 | }, 11 | { 12 | "lw": 50, 13 | "rw": 40, 14 | "p": 0, 15 | "r": 10, 16 | "h": 2, 17 | "lat": "57.556437979751514", 18 | "lng": "18.527285357642654", 19 | "comment": "meter diff 129.25406154945853, precision behöver vara 0.0000001 dicimal degrees för att få 1cm precision" 20 | }, 21 | { 22 | "lw": 50, 23 | "rw": 40, 24 | "p": 10, 25 | "r": 10, 26 | "h": 3 27 | } 28 | ] 29 | -------------------------------------------------------------------------------- /web/mock/socket-mocker.js: -------------------------------------------------------------------------------- 1 | 2 | module.exports = (port, mock) => { 3 | let http = require('http'); 4 | let sockjs = require('sockjs'); 5 | let clients = new Map(); 6 | 7 | let wsServerer = sockjs.createServer({ sockjs_url: 'http://cdn.jsdelivr.net/sockjs/1.0.1/sockjs.min.js' }); 8 | wsServerer.on('connection', (conn) => { 9 | clients.set(conn.id, conn); 10 | console.log(`Websocket client connected, id: ${conn.id}`); 11 | 12 | conn.on('data', (message) => { 13 | console.log('websocket got:' + message); 14 | let json = JSON.parse(message); 15 | 16 | if (json.type === 'forward') { 17 | mock.forward(json.payload.speed, json.payload.turnrate, json.payload.smooth); 18 | } else if (json.type === 'backward') { 19 | mock.backward(json.payload.speed, json.payload.turnrate, json.payload.smooth); 20 | } 21 | 22 | }); 23 | conn.on('close', () => { 24 | console.log(`Websocket client disconnected, id: ${conn.id}`); 25 | clients.delete(conn.id); 26 | }); 27 | }); 28 | 29 | let httpServer = http.createServer(); 30 | wsServerer.installHandlers(httpServer); 31 | httpServer.listen(port, '0.0.0.0'); 32 | 33 | setInterval(() => { 34 | clients.forEach((client) => { 35 | client.write(JSON.stringify({ 36 | type: "status", 37 | payload: mock.getCurrentState(), 38 | })); 39 | }); 40 | 41 | mock.advanceSequence(); 42 | }, 2000); 43 | }; 44 | 45 | 46 | -------------------------------------------------------------------------------- /web/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "liam-esp", 3 | "version": "1.0.0", 4 | "description": "GUI for Liam-ESP", 5 | "private": true, 6 | "author": "Henrik Östman", 7 | "license": "MIT", 8 | "bugs": { 9 | "url": "https://github.com/trycoon/liam-esp/issues" 10 | }, 11 | "repository": { 12 | "type": "git", 13 | "url": "https://github.com/trycoon/liam-esp.git" 14 | }, 15 | "directories": { 16 | "test": "test" 17 | }, 18 | "scripts": { 19 | "dev": "webpack-dev-server --hot --inline --config build/webpack.config.js", 20 | "build": "rimraf ./dist && NODE_ENV=production webpack --config build/webpack.config.js", 21 | "postinstall": "patch-package" 22 | }, 23 | "homepage": "https://github.com/trycoon/liam-esp", 24 | "dependencies": { 25 | "body-parser": "^1.19.0", 26 | "express": "^4.17.1", 27 | "patch-package": "^6.1.2", 28 | "reconnecting-websocket": "^4.1.10" 29 | }, 30 | "devDependencies": { 31 | "@babel/core": "^7.5.4", 32 | "@babel/preset-env": "^7.5.4", 33 | "babel-loader": "^8.0.6", 34 | "clean-webpack-plugin": "^1.0.1", 35 | "compression-webpack-plugin": "^2.0.0", 36 | "cookies": "^0.7.3", 37 | "copy-webpack-plugin": "^4.6.0", 38 | "css-loader": "^2.1.1", 39 | "eslint": "^5.16.0", 40 | "eslint-plugin-import": "^2.18.0", 41 | "extract-text-webpack-plugin": "^4.0.0-beta.0", 42 | "file-loader": "^3.0.1", 43 | "html-webpack-plugin": "^3.2.0", 44 | "mocker-api": "^1.7.6", 45 | "my-local-ip": "^1.0.0", 46 | "node-sass": "^4.12.0", 47 | "rimraf": "^2.6.3", 48 | "sass-loader": "^7.1.0", 49 | "sockjs": "^0.3.19", 50 | "style-loader": "^0.23.1", 51 | "stylelint": "^10.1.0", 52 | "stylelint-webpack-plugin": "^0.10.5", 53 | "url-loader": "^1.1.2", 54 | "webpack": "^4.35.3", 55 | "webpack-cli": "^3.3.6", 56 | "webpack-dev-server": "^3.7.2" 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /web/patches/reconnecting-websocket+4.1.10.patch: -------------------------------------------------------------------------------- 1 | diff --git a/node_modules/reconnecting-websocket/reconnecting-websocket.ts b/node_modules/reconnecting-websocket/reconnecting-websocket.ts 2 | index a93b2f4..971bdd2 100644 3 | --- a/node_modules/reconnecting-websocket/reconnecting-websocket.ts 4 | +++ b/node_modules/reconnecting-websocket/reconnecting-websocket.ts 5 | @@ -292,7 +292,7 @@ export default class ReconnectingWebSocket { 6 | minReconnectionDelay = DEFAULT.minReconnectionDelay, 7 | maxReconnectionDelay = DEFAULT.maxReconnectionDelay, 8 | } = this._options; 9 | - let delay = minReconnectionDelay; 10 | + let delay = 0; 11 | if (this._retryCount > 0) { 12 | delay = 13 | minReconnectionDelay * Math.pow(reconnectionDelayGrowFactor, this._retryCount - 1); 14 | -------------------------------------------------------------------------------- /web/src/api.js: -------------------------------------------------------------------------------- 1 | import * as auth from './authorisation.js'; 2 | import ReconnectingWebSocket from 'reconnecting-websocket'; 3 | alert('använd denna istället: https://sarus.anephenix.com/get-started som websocket lib!'); 4 | alert('använd denna för klarta: https://leafletjs.com/'); 5 | let socket, 6 | socketDisconnectedTimeout; 7 | 8 | $.ajaxSetup({ 9 | cache: false, 10 | timeout: 5000 // 5 seconds 11 | }); 12 | 13 | function showLostConnectionModal() { 14 | document.querySelector('.js-no-connection-modal').style.display = 'block'; 15 | document.querySelector('.js-loginbox').style.display = 'none'; 16 | document.getElementById('modal').style.display = 'block'; 17 | } 18 | 19 | function hideLostConnectionModal() { 20 | document.getElementById('modal').style.display = 'none'; 21 | document.querySelector('.js-no-connection-modal').style.display = 'none'; 22 | document.querySelector('.js-loginbox').style.display = 'none'; 23 | } 24 | 25 | export function setupSocket() { 26 | if (!socket) { 27 | let protocol = location.protocol.indexOf('https') === 0 ? 'wss' : 'ws'; 28 | socket = new ReconnectingWebSocket(`${protocol}://${location.host}/ws`); 29 | 30 | socket.addEventListener('open', () => { 31 | console.info('Got WS connection.'); 32 | if (socketDisconnectedTimeout) { 33 | clearTimeout(socketDisconnectedTimeout); 34 | socketDisconnectedTimeout = undefined; 35 | } 36 | if (!auth.isLoginDialogVisible()) { 37 | hideLostConnectionModal(); 38 | } 39 | }); 40 | 41 | socket.addEventListener('close', () => { 42 | console.info('Lost WS connection.'); 43 | // show lost connection modal if we have not been able to reconnect within 2 seconds. 44 | socketDisconnectedTimeout = setTimeout(() => { 45 | // if we are not currently logging in, show lost connection warning. 46 | if (!auth.isLoginDialogVisible()) { 47 | showLostConnectionModal(); 48 | } 49 | }, 2000); 50 | }); 51 | 52 | socket.addEventListener('error', (error) => { 53 | console.warn(`Got WS error: ${error.message}`); 54 | showLostConnectionModal(); 55 | }); 56 | 57 | // Listen for messages 58 | socket.addEventListener('message', function (event) { 59 | let message = JSON.parse(event.data); 60 | 61 | if (message.type === 'status') { 62 | let status = message.payload; 63 | if (JSON.stringify(status) !== JSON.stringify(liam.data.status)) { 64 | liam.data.status = status; 65 | window.dispatchEvent(new Event('statusUpdated')); 66 | } 67 | } 68 | }); 69 | } 70 | } 71 | 72 | export function socketSend(messageType, payload) { 73 | if (socket && socket.readyState === socket.OPEN) { 74 | socket.send(JSON.stringify({ 75 | type: messageType, 76 | payload: payload 77 | })); 78 | } 79 | } 80 | 81 | export function selectState(state) { 82 | return $.ajax({ 83 | url: '/api/v1/state', 84 | method: 'PUT', 85 | headers: { 86 | 'content-type': 'application/json', 87 | }, 88 | data: JSON.stringify({ 89 | state: state 90 | }) 91 | }); 92 | } 93 | 94 | export function getStatus() { 95 | return $.getJSON('/api/v1/status'); 96 | } 97 | 98 | export function getSystem() { 99 | return $.getJSON('/api/v1/system'); 100 | } 101 | 102 | export function getBatteryHistory() { 103 | return $.getJSON('/api/v1/history/battery'); 104 | } 105 | 106 | export function manual(command, params) { 107 | return $.ajax({ 108 | url: `/api/v1/manual/${command}`, 109 | method: 'PUT', 110 | headers: { 111 | 'content-type': 'application/json', 112 | }, 113 | data: params ? JSON.stringify(params) : '{}' 114 | }); 115 | } 116 | 117 | export function restart() { 118 | return $.ajax({ 119 | url: `/api/v1/reboot`, 120 | method: 'PUT', 121 | headers: { 122 | 'content-type': 'application/json', 123 | }, 124 | data: '{}' 125 | }); 126 | } 127 | 128 | export function factoryreset() { 129 | return $.ajax({ 130 | url: `/api/v1/factoryreset`, 131 | method: 'PUT', 132 | headers: { 133 | 'content-type': 'application/json', 134 | }, 135 | data: '{}' 136 | }); 137 | } 138 | 139 | export function generateNewApiKey() { 140 | return $.ajax({ 141 | url: `/api/v1/apikey`, 142 | method: 'POST', 143 | headers: { 144 | 'content-type': 'application/json', 145 | }, 146 | data: '{}' 147 | }); 148 | } 149 | 150 | export function getLoglevel() { 151 | return $.getJSON('/api/v1/loglevel'); 152 | } 153 | 154 | export function getLogmessages(lastnr) { 155 | return $.getJSON(`/api/v1/logmessages?lastnr=${lastnr || 0}`); 156 | } 157 | 158 | export function setLoglevel(level) { 159 | return $.ajax({ 160 | url: `/api/v1/loglevel`, 161 | method: 'PUT', 162 | headers: { 163 | 'content-type': 'application/json', 164 | }, 165 | data: JSON.stringify({ 166 | level: level 167 | }) 168 | }); 169 | } 170 | 171 | export function createSession(username, password) { 172 | return $.ajax({ 173 | url: `/api/v1/session`, 174 | method: 'POST', 175 | headers: { 176 | 'content-type': 'application/json', 177 | }, 178 | data: JSON.stringify({ 179 | username: username, 180 | password: password 181 | }) 182 | }); 183 | } 184 | 185 | export function getSession() { 186 | return $.getJSON('/api/v1/session'); 187 | } 188 | 189 | export function deleteSession() { 190 | return $.ajax({ 191 | url: `/api/v1/session`, 192 | method: 'DELETE' 193 | }); 194 | } 195 | 196 | export function getScheduleList() { 197 | return $.getJSON('/api/v1/schedules'); 198 | } 199 | 200 | /** 201 | * Add new schedule-entry for mowing 202 | * @param {Array} activeWeekdays array of boolean, where each position represent a weekday and wether that day is selected. 203 | * @param {String} startTime HH:MM of when mower should start mowing 204 | * @param {String} stopTime HH:MM of when mower should stop mowing} activeWeekdays 205 | */ 206 | export function addScheduleEntry(activeWeekdays, startTime, stopTime) { 207 | return $.ajax({ 208 | url: `/api/v1/schedules`, 209 | method: 'POST', 210 | headers: { 211 | 'content-type': 'application/json', 212 | }, 213 | data: JSON.stringify({ 214 | activeWeekdays: activeWeekdays, 215 | startTime: startTime, 216 | stopTime: stopTime 217 | }) 218 | }); 219 | } 220 | 221 | /** 222 | * Delete schedule-entry for mowing 223 | * @param {Number} position 224 | */ 225 | export function removeScheduleEntry(position) { 226 | return $.ajax({ 227 | url: `/api/v1/schedules/` + position, 228 | method: 'DELETE', 229 | headers: { 230 | 'content-type': 'application/json', 231 | } 232 | }); 233 | } 234 | -------------------------------------------------------------------------------- /web/src/authorisation.js: -------------------------------------------------------------------------------- 1 | import * as api from './api.js'; 2 | let submitHandler, loginPromise; 3 | 4 | /** 5 | * show login dialog, returns a promise that resolves when login is successful. 6 | */ 7 | export function showLogin() { 8 | if (loginPromise) { 9 | return loginPromise; 10 | } else { 11 | loginPromise = new Promise((resolve) => { 12 | let loginBox = document.querySelector('.js-loginbox'); 13 | let username = loginBox.querySelector('.js-username'); 14 | let password = loginBox.querySelector('.js-password'); 15 | let submit = loginBox.querySelector('.js-submit'); 16 | let messageBox = loginBox.querySelector('.js-message'); 17 | messageBox.textContent = ''; 18 | loginBox.style.display = 'block'; 19 | 20 | document.querySelector('.js-no-connection-modal').style.display = 'none'; 21 | document.getElementById('modal').style.display = 'block'; 22 | username.focus(); 23 | 24 | // make sure we remove old eventlisteners first so we don't trigger twice. 25 | if (typeof submitHandler === 'function') { 26 | submit.removeEventListener('click', submitHandler); 27 | } 28 | 29 | submitHandler = (evt) => { 30 | loginBox.classList.remove('shake'); 31 | 32 | api.createSession(username.value, password.value) 33 | .done(result => { 34 | document.getElementById('modal').style.display = 'none'; 35 | loginBox.style.display = 'none'; 36 | messageBox.textContent = ''; 37 | loginPromise = null; // allow future logins. 38 | resolve(result); 39 | }) 40 | .catch(error => { 41 | if (error.status === 401) { 42 | password.value = ''; 43 | messageBox.textContent = 'username or password incorrect'; 44 | loginBox.classList.add('shake'); 45 | } else { 46 | messageBox.textContent = 'unknown error, retry later'; 47 | loginBox.classList.add('shake'); 48 | console.error('Failed to login. error: ' + error.message); 49 | } 50 | }) 51 | evt.preventDefault(); 52 | } 53 | 54 | submit.addEventListener('click', submitHandler); 55 | }); 56 | 57 | return loginPromise; 58 | } 59 | } 60 | 61 | export function isLoginDialogVisible() { 62 | return !!loginPromise; 63 | } -------------------------------------------------------------------------------- /web/src/favicons/android-chrome-192x192.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/android-chrome-192x192.png -------------------------------------------------------------------------------- /web/src/favicons/android-chrome-512x512.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/android-chrome-512x512.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon-120x120.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon-120x120.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon-152x152.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon-152x152.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon-180x180.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon-180x180.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon-60x60.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon-60x60.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon-76x76.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon-76x76.png -------------------------------------------------------------------------------- /web/src/favicons/apple-touch-icon.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/apple-touch-icon.png -------------------------------------------------------------------------------- /web/src/favicons/browserconfig.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | #da532c 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /web/src/favicons/favicon-16x16.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/favicon-16x16.png -------------------------------------------------------------------------------- /web/src/favicons/favicon-32x32.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/favicon-32x32.png -------------------------------------------------------------------------------- /web/src/favicons/favicon.ico: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/favicon.ico -------------------------------------------------------------------------------- /web/src/favicons/mstile-150x150.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/favicons/mstile-150x150.png -------------------------------------------------------------------------------- /web/src/favicons/site.webmanifest: -------------------------------------------------------------------------------- 1 | { 2 | "name": "Liam-ESP", 3 | "short_name": "Liam-ESP", 4 | "icons": [ 5 | { 6 | "src": "/android-chrome-192x192.png", 7 | "sizes": "192x192", 8 | "type": "image/png" 9 | }, 10 | { 11 | "src": "/android-chrome-512x512.png", 12 | "sizes": "512x512", 13 | "type": "image/png" 14 | } 15 | ], 16 | "theme_color": "#ffffff", 17 | "background_color": "#ffffff", 18 | "start_url": "http://liam.smart-home.rocks", 19 | "display": "standalone" 20 | } 21 | -------------------------------------------------------------------------------- /web/src/html/swagger/swagger.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | Liam-ESP API 6 | 7 | 8 | 9 | 10 |
11 | 12 | 13 | 38 | 39 | 40 | -------------------------------------------------------------------------------- /web/src/index.js: -------------------------------------------------------------------------------- 1 | import './styles/main.scss' 2 | import * as api from './api.js'; 3 | import * as auth from './authorisation.js'; 4 | import * as sectionMap from './sections/map.js'; 5 | import * as sectionInfo from './sections/info.js'; 6 | import * as sectionManual from './sections/manual.js'; 7 | import * as sectionMetrics from './sections/metrics.js'; 8 | import * as sectionSettings from './sections/settings.js'; 9 | import * as sectionSchedule from './sections/schedule.js'; 10 | import * as sectionStart from './sections/start.js'; 11 | 12 | // store for local state. 13 | global.liam = { 14 | config: {}, 15 | data: { 16 | status: {}, 17 | system: {}, 18 | }, 19 | sections: { 20 | start: sectionStart, 21 | manual: sectionManual, 22 | metrics: sectionMetrics, 23 | settings: sectionSettings, 24 | schedule: sectionSchedule, 25 | info: sectionInfo, 26 | map: sectionMap, 27 | } 28 | }; 29 | 30 | let currentActiveSection, 31 | lastUptime = 0; 32 | 33 | function setTheme(name) { 34 | $('html').addClass(name ? 'theme-' + name : liam.config.theme ? 'theme-' + liam.config.theme : 'theme-default'); 35 | } 36 | 37 | window.addEventListener('statusUpdated', () => { 38 | // if mower has been restarted then reload client also. This is to make sure that we have the latest client-software running in case mower has been restarted due to a firmware update. 39 | if (liam.data.status.uptime < lastUptime) { 40 | location.reload(true); 41 | } else { 42 | lastUptime = liam.data.status.uptime; 43 | } 44 | }); 45 | 46 | function showSection(section) { 47 | let sections = $('.js-section'), 48 | navItems = $('.js-main-nav-item'), 49 | sectionEl = $('.js-section-' + section), 50 | navSectionEl = $('.js-nav-section-' + section); 51 | 52 | navItems.removeClass('active'); 53 | navSectionEl.addClass('active'); 54 | sections.hide(); 55 | sectionEl.show(); 56 | 57 | if (currentActiveSection) { 58 | currentActiveSection.unselected(); 59 | } 60 | 61 | currentActiveSection = liam.sections[section]; 62 | currentActiveSection.selected(); 63 | } 64 | 65 | function initialSetup() { 66 | // get initial settings and system information. 67 | $.when( 68 | api.getSystem(), 69 | api.getStatus() 70 | ).done((system, status) => { 71 | liam.data.system = system[0]; 72 | liam.data.status = status[0]; 73 | 74 | for (let section in global.liam.sections) { 75 | global.liam.sections[section].init(); 76 | } 77 | 78 | window.dispatchEvent(new Event('statusUpdated')); 79 | showSection('start'); 80 | 81 | api.setupSocket(); 82 | }).catch(error => { 83 | if (error.status === 401) { 84 | auth.showLogin().then(() => { 85 | initialSetup(); 86 | }); 87 | } else { 88 | setTimeout(initialSetup, 500); // retry if failed. 89 | } 90 | }); 91 | } 92 | 93 | function init() { 94 | // Hide all sections first, showSection() will show the appropriate one. 95 | $('.section').hide(); 96 | $('.js-main-nav').on('click', '.js-main-nav-item', function() { 97 | showSection($(this).data('section')); 98 | }); 99 | 100 | setTheme(); 101 | initialSetup(); 102 | } 103 | 104 | // Start application. 105 | init(); -------------------------------------------------------------------------------- /web/src/maputils.js: -------------------------------------------------------------------------------- 1 | const radiusAtEquator = 637813700, // in cenitmeter 2 | radiusAtPole = 635675230; 3 | 4 | 5 | // more useful stuff https://github.com/chrisveness/geodesy 6 | 7 | /** 8 | * Return the earth circumference (in centimeters) at given latitude and height above sea 9 | * @param {*} latitude 10 | * @param {*} heightAboveSea height above sealevel (in meters) 11 | */ 12 | export function earthCircumference(latitude, heightAboveSea) { 13 | 14 | latitude *= Math.PI / 180; 15 | // taken from https://rechneronline.de/earth-radius 16 | // latitude B, radius R, radius at equator r1, radius at pole r2 17 | // R = √ [ (r1² * cos(B))² + (r2² * sin(B))² ] / [ (r1 * cos(B))² + (r2 * sin(B))² ] 18 | let radius = Math.sqrt( 19 | (Math.pow(radiusAtEquator * radiusAtEquator * Math.cos(latitude), 2) + Math.pow(radiusAtPole * radiusAtPole * Math.sin(latitude), 2)) / 20 | (Math.pow(radiusAtEquator * Math.cos(latitude), 2) + Math.pow(radiusAtPole * Math.sin(latitude), 2)) 21 | ) + heightAboveSea * 100; 22 | 23 | return 2 * radius * Math.PI; 24 | } 25 | -------------------------------------------------------------------------------- /web/src/resources/3d_mower.blend: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/3d_mower.blend -------------------------------------------------------------------------------- /web/src/resources/3d_mower.glb: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/3d_mower.glb -------------------------------------------------------------------------------- /web/src/resources/battery.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 44 | Svg Vector Icons : http://www.onlinewebfonts.com/icon image/svg+xml 55 | 120 | -------------------------------------------------------------------------------- /web/src/resources/body.fbx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/body.fbx -------------------------------------------------------------------------------- /web/src/resources/disc.fbx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/disc.fbx -------------------------------------------------------------------------------- /web/src/resources/guide.fbx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/guide.fbx -------------------------------------------------------------------------------- /web/src/resources/housing.fbx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/housing.fbx -------------------------------------------------------------------------------- /web/src/resources/panel_1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/panel_1.jpg -------------------------------------------------------------------------------- /web/src/resources/panel_2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/panel_2.jpg -------------------------------------------------------------------------------- /web/src/resources/wheel.fbx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/trycoon/liam-esp/08e543e89b853a0b2b1df0b2dce69747d89a9063/web/src/resources/wheel.fbx -------------------------------------------------------------------------------- /web/src/sections/info.js: -------------------------------------------------------------------------------- 1 | import * as api from '../api.js'; 2 | let interval, 3 | requestInProgress, 4 | logmessages = [], 5 | syslogTextArea = document.getElementById('syslog'), 6 | syslogTailCheckbox = document.getElementById('tailSyslog'), 7 | lastLogNr = 0; 8 | 9 | function renderInfo() { 10 | let info = liam.data.system; 11 | $('.js-section-info .appName').text(info.name); 12 | $('.js-section-info .appVersion').text(info.version); 13 | $('.js-section-info .mowerId').text(info.mowerId); 14 | $('.js-section-info .localTime').text(info.localTime); 15 | } 16 | 17 | function getSystemInfoAndRender() { 18 | if (requestInProgress) { 19 | return; 20 | } 21 | 22 | requestInProgress = true; 23 | 24 | $.when( 25 | api.getSystem(), 26 | api.getLogmessages(lastLogNr) 27 | ).done((r1, r2) => { 28 | liam.data.system = r1[0]; 29 | renderInfo(); 30 | 31 | logmessages = logmessages.concat(r2[0].messages); 32 | lastLogNr = r2[0].lastnr; 33 | 34 | syslogTextArea.value = logmessages.join('\n'); 35 | 36 | if (syslogTailCheckbox.checked) { 37 | syslogTextArea.scrollTop = syslogTextArea.scrollHeight; 38 | } 39 | }) 40 | .always(() => { 41 | requestInProgress = false; 42 | }); 43 | } 44 | 45 | function uptimeFormat(seconds) { 46 | let day, hour, minute; 47 | 48 | minute = Math.floor(seconds / 60); 49 | seconds = seconds % 60; 50 | hour = Math.floor(minute / 60); 51 | minute = minute % 60; 52 | day = Math.floor(hour / 24); 53 | hour = hour % 24; 54 | 55 | return `${day} days, ${hour} hours, ${minute} min, ${seconds} sec`; 56 | } 57 | 58 | function updatedStatus() { 59 | let status = liam.data.status; 60 | 61 | // https://www.metageek.com/training/resources/understanding-rssi.html 62 | 63 | let wifiQuality = ''; 64 | if (status.wifiSignal > -40) { 65 | wifiQuality = 'Excellent'; 66 | } else if (status.wifiSignal > -68) { 67 | wifiQuality = 'Very good'; 68 | } else if (status.wifiSignal > -71) { 69 | wifiQuality = 'Good'; 70 | } else if (status.wifiSignal > -81) { 71 | wifiQuality = 'Poor'; 72 | } else { 73 | wifiQuality = 'Unusable'; 74 | } 75 | 76 | $('.js-section-info .wifiSignal').text(`${wifiQuality} (${status.wifiSignal} dBm)`); 77 | $('.js-section-info .uptime').html(uptimeFormat(status.uptime)); 78 | } 79 | 80 | export function selected() { 81 | renderInfo(); // render the information we already got 82 | getSystemInfoAndRender(); // and then get fresh ones 83 | interval = setInterval(() => { 84 | getSystemInfoAndRender(); // and keep on fetching updated system information as long as the user view this tab 85 | }, 5000); 86 | } 87 | 88 | export function unselected() { 89 | clearInterval(interval); 90 | } 91 | 92 | export function init() { 93 | window.addEventListener('statusUpdated', updatedStatus); 94 | } 95 | -------------------------------------------------------------------------------- /web/src/sections/manual.js: -------------------------------------------------------------------------------- 1 | import * as api from '../api.js'; 2 | import * as auth from '../authorisation.js'; 3 | import { Joystick } from '../components/joystick.js'; 4 | 5 | let startMowerButton, 6 | stopMowerButton, 7 | joystick; 8 | 9 | export function selected() { 10 | stop(); 11 | } 12 | 13 | export function unselected() { 14 | stop(); 15 | } 16 | 17 | function stop() { 18 | api.manual("stop") 19 | .catch(error => { 20 | if (error.status === 401) { 21 | auth.showLogin().then(() => { 22 | stop(); 23 | }); 24 | } else { 25 | // keep on trying if we failed 26 | setTimeout(() => { 27 | stop(); 28 | }, 400); 29 | } 30 | }); 31 | } 32 | 33 | function startMowerMotor() { 34 | api.manual("cutter_on") 35 | .catch(error => { 36 | if (error.status === 401) { 37 | auth.showLogin().then(() => { 38 | startMowerMotor(); 39 | }); 40 | } else { 41 | console.error(error.message); 42 | } 43 | }); 44 | } 45 | 46 | function stopMowerMotor() { 47 | api.manual("cutter_off") 48 | .catch(error => { 49 | if (error.status === 401) { 50 | auth.showLogin().then(() => { 51 | stopMowerMotor(); 52 | }); 53 | } else { 54 | // keep on trying if we failed 55 | setTimeout(() => { 56 | stopMowerMotor(); 57 | }, 400); 58 | } 59 | }); 60 | } 61 | 62 | function updatedStatus() { 63 | 64 | if (!liam.data.status) { 65 | return; 66 | } 67 | 68 | if (liam.data.status.cutterRotating) { 69 | startMowerButton.hide(); 70 | stopMowerButton.show(); 71 | } else { 72 | startMowerButton.show(); 73 | stopMowerButton.hide(); 74 | } 75 | } 76 | 77 | export function init() { 78 | 79 | let sec = $('.js-section-manual'); 80 | 81 | startMowerButton = sec.find('.js-startmower'); 82 | startMowerButton.on('click', () => { 83 | startMowerMotor(); 84 | }); 85 | 86 | stopMowerButton = sec.find('.js-stopmower'); 87 | stopMowerButton.on('click', () => { 88 | stopMowerMotor(); 89 | }); 90 | 91 | joystick = new Joystick(document.getElementById('manual_joystick')); 92 | joystick.on('stop', () => stop()); 93 | joystick.on('move', movement => { 94 | api.socketSend(movement.forward ? "forward" : "backward", { 95 | speed: movement.speed, 96 | turnrate: movement.turnrate, 97 | smooth: true 98 | }); 99 | }); 100 | 101 | window.addEventListener('statusUpdated', updatedStatus); 102 | updatedStatus(); 103 | } 104 | -------------------------------------------------------------------------------- /web/src/sections/map.js: -------------------------------------------------------------------------------- 1 | import * as api from '../api.js'; 2 | import * as mapUtils from '../maputils.js'; 3 | import { Joystick } from '../components/joystick.js'; 4 | 5 | let joystick; 6 | 7 | export function selected() { 8 | // TODO: https://github.com/taroz/GNSS-Radar ("skyplot"), switch charist to Highchart for more functionality. 9 | } 10 | 11 | export function unselected() { 12 | 13 | } 14 | 15 | export function init() { 16 | 17 | joystick = new Joystick(document.getElementById('map_joystick')); 18 | /*joystick.on('stop', () => stop()); 19 | joystick.on('move', movement => { 20 | api.socketSend(movement.forward ? "forward" : "backward", { 21 | speed: movement.speed, 22 | turnrate: movement.turnrate, 23 | smooth: true 24 | }); 25 | });*/ 26 | 27 | } 28 | -------------------------------------------------------------------------------- /web/src/sections/schedule.js: -------------------------------------------------------------------------------- 1 | import * as api from '../api.js'; 2 | 3 | const MAX_SCHEDULE_ENTRIES = 10; 4 | let scheduleListEl = document.getElementById('scheduleList'), 5 | scheduleEntries = 0; 6 | 7 | /** 8 | * Generate HTML fragment for a schedule entry. 9 | * @param {Number} position position in schedule list 10 | * @param {Array} activeWeekdays array of boolean, where each position represent a weekday and wether that day is selected. 11 | * @param {String} startTime HH:MM of when mower should start mowing 12 | * @param {String} stopTime HH:MM of when mower should stop mowing 13 | * @returns {String} HTML fragment 14 | */ 15 | function getScheduleEntryFragment(position, activeWeekdays, startTime, stopTime) { 16 | 17 | let dayList = ['Mon', 'Tue', 'Wed', 'Thu', 'Fri', 'Sat', 'Sun'].map((day, index) => { 18 | return `${day}`; 19 | }).join(''); 20 | 21 | return ` 22 |
  • 23 |
    24 | ${dayList} 25 |
    26 |
    27 | ${startTime} - ${stopTime} 28 |
    29 | 30 |
    31 |
    32 |
  • 33 | ` 34 | } 35 | 36 | function addScheduleEntry() { 37 | 38 | const timeRegExp = /(00|01|02|03|04|05|06|07|08|09|10|11|12|13|14|15|16|17|18|19|20|21|22|23):(0|1|2|3|4|5)\d/g; 39 | let startTime = `${document.getElementById('js-startHour').value}:${document.getElementById('js-startMin').value}`, 40 | stopTime = `${ document.getElementById('js-stopHour').value}:${document.getElementById('js-stopMin').value}`, 41 | weekDayButtons = [ ...document.querySelectorAll('#js-addScheduleButtons input') ], 42 | activeWeekdays = weekDayButtons.map(day => { 43 | return day.checked; 44 | }); 45 | 46 | // check that atleast one day of week is selected, that start- and stoptime is valid, and that there is no more than 10 schedules. 47 | if (!activeWeekdays.every(selected => {return selected === false}) && startTime.match(timeRegExp) && stopTime.match(timeRegExp) && scheduleEntries < MAX_SCHEDULE_ENTRIES) { 48 | $.when(api.addScheduleEntry(activeWeekdays, startTime, stopTime)) 49 | .done(() => { 50 | renderScheduleList(); 51 | }); 52 | } 53 | } 54 | 55 | function removeScheduleEntry(event) { 56 | 57 | $.when(api.removeScheduleEntry(event.currentTarget.dataset.pos)) 58 | .done(() => { 59 | renderScheduleList(); 60 | }); 61 | 62 | } 63 | 64 | function renderScheduleList() { 65 | 66 | $.when(api.getScheduleList()) 67 | .done(schedules => { 68 | // remove old list first 69 | [ ...scheduleListEl.childNodes ].forEach(el => el.remove()); 70 | 71 | scheduleEntries = schedules.length; 72 | 73 | document.querySelector('.js-activeSchedules').textContent = `(${scheduleEntries}/${MAX_SCHEDULE_ENTRIES})`; 74 | 75 | schedules.forEach((entry, index) => { 76 | 77 | let listItem = document.createRange().createContextualFragment(getScheduleEntryFragment(index, entry.activeWeekdays, entry.startTime, entry.stopTime)); 78 | listItem.querySelector('.js-removeSchedule').addEventListener('click', removeScheduleEntry); 79 | 80 | scheduleListEl.appendChild(listItem); 81 | 82 | }); 83 | 84 | if (schedules.length === 0) { 85 | scheduleListEl.appendChild(document.createTextNode("No active schedule! Add one above.")); 86 | } 87 | }); 88 | 89 | } 90 | 91 | export function selected() { 92 | 93 | renderScheduleList(); 94 | 95 | } 96 | 97 | export function unselected() { 98 | 99 | } 100 | 101 | export function init() { 102 | 103 | document.getElementById('js-addSchedule').addEventListener('click', addScheduleEntry); 104 | 105 | } 106 | -------------------------------------------------------------------------------- /web/src/sections/settings.js: -------------------------------------------------------------------------------- 1 | import * as api from '../api.js'; 2 | import * as auth from '../authorisation.js'; 3 | 4 | let sec = $('.js-section-settings'); 5 | 6 | export function selected() { 7 | api.getSystem() 8 | .then(function(data) { 9 | liam.data.system = data; 10 | sec.find('#apikey').val(data.apiKey); 11 | }) 12 | .catch(error => { 13 | if (error.status === 401) { 14 | auth.showLogin().then(() => { 15 | selected(); 16 | }); 17 | } else { 18 | console.error(e.message); 19 | } 20 | }); 21 | 22 | api.getLoglevel() 23 | .then(function(data) { 24 | $(`#loglever option[value="${data.level}"]`).prop('selected', true); 25 | }) 26 | .catch(function(e) { 27 | console.error(e.message); 28 | }); 29 | } 30 | 31 | export function unselected() { 32 | 33 | } 34 | 35 | function restart() { 36 | api.restart() 37 | .catch(error => { 38 | if (error.status === 401) { 39 | auth.showLogin().then(() => { 40 | restart(); 41 | }); 42 | } else { 43 | console.error(e.message); 44 | } 45 | }); 46 | } 47 | 48 | function factoryreset() { 49 | api.factoryreset() 50 | .catch(error => { 51 | if (error.status === 401) { 52 | auth.showLogin().then(() => { 53 | factoryreset(); 54 | }); 55 | } else { 56 | console.error(e.message); 57 | } 58 | }); 59 | } 60 | 61 | export function init() { 62 | sec.find('.js-restart').on('click', function() { 63 | restart(); 64 | }); 65 | sec.find('.js-factoryreset').on('click', function() { 66 | if (confirm('Are you sure you want to wipe ALL settings and return mower to "factory" defaults?')) { 67 | factoryreset(); 68 | } 69 | }); 70 | sec.find('#loglever').change(function() { 71 | api.setLoglevel(parseInt(this.value)) 72 | .then(function() { 73 | alert("You must reboot system for loglevel changes to be used.") 74 | }) 75 | .catch(function(e) { 76 | console.error(e.message); 77 | }); 78 | }); 79 | sec.find('.js-generateApiKey').on('click', function() { 80 | api.generateNewApiKey() 81 | .then(function() { 82 | api.getSystem() 83 | .then(function(data) { 84 | liam.data.system = data; 85 | sec.find('#apikey').val(data.apiKey); 86 | }) 87 | .catch(function(e) { 88 | console.error(e.message); 89 | }); 90 | }) 91 | .catch(function(e) { 92 | console.error(e.message); 93 | }); 94 | }); 95 | } --------------------------------------------------------------------------------