From 28b4957175456f386a8c34ae5d9bc62d239ddc7c Mon Sep 17 00:00:00 2001 From: David Beechey Date: Wed, 23 Oct 2024 17:34:05 +0100 Subject: [PATCH 1/8] Update README (#37) --- README.md | 118 +++++++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 117 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 8b54885..c33f87f 100644 --- a/README.md +++ b/README.md @@ -5,5 +5,121 @@ - The HYPED logo. + The HYPED logo. + +  + +![Build Shield](https://github.com/Hyp-ed/hyped-2025/actions/workflows/ci.yml/badge.svg) ![TODO Shield](https://img.shields.io/github/search/hyp-ed/hyped-2025/TODOLater?color=red&label=TODO%20counter) + +## Software Architecture + +This repository contains the software for the HYPED 2025 pod. The software is divided into two main components: + +### 1. Pod-side Code + +The pod-side code is responsible for controlling the pod's systems, including the motor & levitation controllers, sensors, localisation system, and communication with the base station. The pod-side code is written in Rust using [Embassy](https://embassy.dev/) and runs on the pod's STM32 microcontrollers. + +We use the following microcontrollers on our pod: + +- [STM32L476RG](https://www.st.com/en/microcontrollers-microprocessors/stm32l476rg.html) +- [STM32F767ZI](https://www.st.com/en/microcontrollers-microprocessors/stm32f767zi.html) +- [STM32H743](https://www.st.com/en/microcontrollers-microprocessors/stm32h743zi.html) +- [STM23L432](https://www.st.com/en/microcontrollers-microprocessors/stm32l432kc.html) + +| Sub-system | Microcontroller | Number | +| ------------------ | --------------- | ------ | +| Localisation | STM32H743 | 1 | +| Telemetry | STM32H743 | 1 | +| Levitation control | STM32F767 | TBD | +| Motor control | TBD | 1 | + +All microcontrollers on our pod will communicate with each other (for sending sensor data, commands, logs, etc.) using [CAN](https://en.wikipedia.org/wiki/CAN_bus) (Controller Area Network). + +### 2. Base Station (Telemetry) + +The base station (aka Telemetry) is responsible for monitoring the pod's systems, visualising data, and sending commands to the pod. The Telemetry system is written in TypeScript and runs on a base station computer connected to the pod via 2.4GHz radio antennas ([Ubiquiti Rocket M2s](https://techspecs.ui.com/uisp/wireless/rocketm2)). (On the pod-side, the Telemetry board is connected to one of the Rockets and relays messages onto the other microcontrollers over CAN.) The [MQTT](https://mqtt.org/) IoT messaging protocol is used to transfer messages between the pod and the base station. + +The base station consists of two main components: + +- The Telemetry server, which communicates with the pod and serves the GUI. +- The Telemetry GUI, which visualises data and allows the user to send commands to the pod. + +You can learn more about our Telemetry system on our Wiki [here](https://github.com/Hyp-ed/hyped-2025/wiki/What-is-Telemetry). + +## Dependencies + +### Pod-side Code (Rust) + +- [Rust](https://www.rust-lang.org/tools/install) +- [probe-rs](https://probe.rs/guide/getting-started/) + +Our Wiki contains a guide on how to get started with Rust and `probe-rs` [here](https://github.com/Hyp-ed/hyped-2025/wiki/Getting-Started-with-Rust). + +### Base Station (Node.js) + +- [Node.js](https://nodejs.org/en/download/) +- [pnpm](https://pnpm.io/installation) + +Or if running with Docker (recommended, see usage section): + +- [Docker](https://docs.docker.com/get-docker/) + +For more details on how to set up a development environment for the Telemetry system, see our Wiki [here](https://github.com/Hyp-ed/hyped-2025/wiki/Telemetry-Development) + +## Usage + +### Pod-side + +To flash some code to an STM32 microcontroller, first navigate to the `boards` directory and then to the board-specific directory. For example, to run code on the `stm32f476rg` board you would first change directory into `boards/stm32f476rg`. + +Then, to flash some particular code to the microcontroller, `bin/{your_code}.rs`, run the following command: + +```bash +cargo run --bin {your_code} +``` + +### Base Station (Telemetry) + +> Note: The following should be run in the `telemetry` directory. + +To run the telemetry system, run the following command: + +``` +./telemetry.sh -m +``` + +where `` is one of the scripts defined in `package.json`. E.g. `dev` or `build`. For a full list of possible arguments, run `./telemetry.sh --help`. + +> The GUI will now be available on `http://localhost:5173` + +## Repository Structure + +Our repository is structured as follows: + +- `telemetry/`: Contains the base station code for the Telemetry server and GUI. +- `lib/`: Contains the shared library code for the pod-side code and the base station. + - `lib/core/`: Contains the core library code. + - `lib/io/`: Contains our abstracted IO implementations. + - `lib/sensors/`: Contains our sensor implementations. +- `boards/`: Contains the board-specific code for the pod-side code. These implementations are specific to each of the STM32 microcontrollers we are using due to differences in the peripherals available on each microcontroller. The board-specific code includes hardware implementations of the IO traits defined in `lib/io/`, tasks that can run on the board, as well as binaries that can be flashed to the board. + - `boards/{board_name}/src/io`: The hardware implementations of the IO traits. + - `boards/{board_name}/src/tasks`: The tasks that can run on the board. + - `boards/{board_name}/src/bin`: The binaries that can be flashed to the board. + +## Contributing + +### Rust + +We have a GitHub Actions workflow that runs on every pull request to ensure that the code compiles and passes tests. We also lint all of our code using `clippy`, which is a collection of lints to catch common mistakes, and check that the code is formatted correctly using `rustfmt`. We also check that everything is spelled correctly using `typos`. + +### TypeScript + +TypeScript code is linted using `ESLint` and formatted using `Prettier`. The configuration for these tools can be found in the `eslint-config` package and the `.prettierrc` file respectively. You can also find our global TypeScript configuration in the `tsconfig` package. + +To run the linter and formatter, use the following commands: + +- `pnpm lint` to check for lint errors, or `pnpm lint:fix` to automatically fix some issues. +- `pnpm format` to format the code, or `pnpm format:check` to check for formatting errors but not format. + +Like our Rust code, we have a GitHub Actions workflow to check that these tools pass on every pull request. From 75de789ace159507528d2dcd9cbe224c0e833c7c Mon Sep 17 00:00:00 2001 From: David Beechey Date: Fri, 25 Oct 2024 15:24:36 +0100 Subject: [PATCH 2/8] SNS - Create `HypedSpi` trait (#38) --- lib/io/src/lib.rs | 1 + lib/io/src/spi.rs | 22 ++++++++++++++++++++++ 2 files changed, 23 insertions(+) create mode 100644 lib/io/src/spi.rs diff --git a/lib/io/src/lib.rs b/lib/io/src/lib.rs index 927fae6..7040188 100644 --- a/lib/io/src/lib.rs +++ b/lib/io/src/lib.rs @@ -2,3 +2,4 @@ pub mod gpio; pub mod i2c; +pub mod spi; diff --git a/lib/io/src/spi.rs b/lib/io/src/spi.rs new file mode 100644 index 0000000..479dc78 --- /dev/null +++ b/lib/io/src/spi.rs @@ -0,0 +1,22 @@ +/// SPI errors that can occur +/// From: https://docs.embassy.dev/embassy-stm32/git/stm32f103c8/spi/enum.Error.html +pub enum SpiError { + Framing, + Crc, + ModeFault, + Overrun, +} + +/// A word is either u8 or u16 +pub enum WordSize { + U8(u8), + U16(u16), +} + +/// SPI trait used to abstract SPI and allow for mocking +pub trait HypedSpi { + /// Read data into `words` from the SPI sensor + fn read(&mut self, words: &mut [WordSize]) -> Result<(), SpiError>; + /// Write data from `words` to the SPI sensor + fn write(&mut self, words: &[WordSize]) -> Result<(), SpiError>; +} From 0e7a8065f8163bf52179d5e0d0bf7626a9cf726a Mon Sep 17 00:00:00 2001 From: David Beechey Date: Fri, 25 Oct 2024 15:36:05 +0100 Subject: [PATCH 3/8] INFRA - Add STM32F767ZI board support (#35) --- .github/workflows/ci.yml | 2 + Cargo.toml | 1 + boards/stm32f767zi/.cargo/config.toml | 9 + boards/stm32f767zi/Cargo.lock | 905 ++++++++++++++++++++ boards/stm32f767zi/Cargo.toml | 27 + boards/stm32f767zi/build.rs | 5 + boards/stm32f767zi/src/bin/keyence_test.rs | 16 + boards/stm32f767zi/src/bin/temp_test.rs | 16 + boards/stm32f767zi/src/io.rs | 2 + boards/stm32f767zi/src/io/gpio.rs | 20 + boards/stm32f767zi/src/io/i2c.rs | 51 ++ boards/stm32f767zi/src/lib.rs | 4 + boards/stm32f767zi/src/tasks.rs | 2 + boards/stm32f767zi/src/tasks/keyence.rs | 17 + boards/stm32f767zi/src/tasks/temperature.rs | 45 + boards/stm32l476rg/Cargo.toml | 12 - boards/stm32l476rg/src/io/gpio.rs | 4 +- lib/io/src/gpio.rs | 4 +- lib/io/src/i2c.rs | 6 +- lib/sensors/src/keyence.rs | 6 +- 20 files changed, 1132 insertions(+), 22 deletions(-) create mode 100644 boards/stm32f767zi/.cargo/config.toml create mode 100644 boards/stm32f767zi/Cargo.lock create mode 100644 boards/stm32f767zi/Cargo.toml create mode 100644 boards/stm32f767zi/build.rs create mode 100644 boards/stm32f767zi/src/bin/keyence_test.rs create mode 100644 boards/stm32f767zi/src/bin/temp_test.rs create mode 100644 boards/stm32f767zi/src/io.rs create mode 100644 boards/stm32f767zi/src/io/gpio.rs create mode 100644 boards/stm32f767zi/src/io/i2c.rs create mode 100644 boards/stm32f767zi/src/lib.rs create mode 100644 boards/stm32f767zi/src/tasks.rs create mode 100644 boards/stm32f767zi/src/tasks/keyence.rs create mode 100644 boards/stm32f767zi/src/tasks/temperature.rs diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 262f3c8..1be9d12 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -25,3 +25,5 @@ jobs: - run: rustup target add thumbv7em-none-eabihf - run: cargo build --verbose working-directory: boards/stm32l476rg + - run: cargo build --verbose + working-directory: boards/stm32f767zi diff --git a/Cargo.toml b/Cargo.toml index a560826..158ab8e 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -5,5 +5,6 @@ members = [ ] exclude = [ "boards/stm32l476rg", + "boards/stm32f767zi", ] resolver = "2" \ No newline at end of file diff --git a/boards/stm32f767zi/.cargo/config.toml b/boards/stm32f767zi/.cargo/config.toml new file mode 100644 index 0000000..def2492 --- /dev/null +++ b/boards/stm32f767zi/.cargo/config.toml @@ -0,0 +1,9 @@ +[target.'cfg(all(target_arch = "arm", target_os = "none"))'] +# replace STM32F429ZITx with your chip as listed in `probe-rs chip list` +runner = "probe-rs run --chip STM32F767ZITx" + +[build] +target = "thumbv7em-none-eabihf" + +[env] +DEFMT_LOG = "debug,smoltcp=info" diff --git a/boards/stm32f767zi/Cargo.lock b/boards/stm32f767zi/Cargo.lock new file mode 100644 index 0000000..0a1abc3 --- /dev/null +++ b/boards/stm32f767zi/Cargo.lock @@ -0,0 +1,905 @@ +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "autocfg" +version = "1.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ace50bade8e6234aa140d9a2f552bbee1db4d353f69b8217bc503490fc1a9f26" + +[[package]] +name = "bare-metal" +version = "0.2.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" +dependencies = [ + "rustc_version", +] + +[[package]] +name = "bit_field" +version = "0.10.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dc827186963e592360843fb5ba4b973e145841266c1357f7180c43526f2e5b61" + +[[package]] +name = "bitfield" +version = "0.13.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" + +[[package]] +name = "bitflags" +version = "1.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" + +[[package]] +name = "bitflags" +version = "2.6.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b048fb63fd8b5923fc5aa7b340d8e156aec7ec02f0c78fa8a6ddc2613f6f71de" + +[[package]] +name = "byteorder" +version = "1.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1fd0f2584146f6f2ef48085050886acf353beff7305ebd1ae69500e27c67f64b" + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "cortex-m" +version = "0.7.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" +dependencies = [ + "bare-metal", + "bitfield", + "critical-section", + "embedded-hal 0.2.7", + "volatile-register", +] + +[[package]] +name = "cortex-m-rt" +version = "0.7.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" +dependencies = [ + "cortex-m-rt-macros", +] + +[[package]] +name = "cortex-m-rt-macros" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" +dependencies = [ + "proc-macro2", + "quote", + "syn 1.0.109", +] + +[[package]] +name = "critical-section" +version = "1.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f64009896348fc5af4222e9cf7d7d82a95a256c634ebcf61c53e4ea461422242" + +[[package]] +name = "darling" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6f63b86c8a8826a49b8c21f08a2d07338eec8d900540f8630dc76284be802989" +dependencies = [ + "darling_core", + "darling_macro", +] + +[[package]] +name = "darling_core" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "95133861a8032aaea082871032f5815eb9e98cef03fa916ab4500513994df9e5" +dependencies = [ + "fnv", + "ident_case", + "proc-macro2", + "quote", + "strsim", + "syn 2.0.79", +] + +[[package]] +name = "darling_macro" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d336a2a514f6ccccaa3e09b02d41d35330c07ddf03a62165fcec10bb561c7806" +dependencies = [ + "darling_core", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "defmt" +version = "0.3.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a99dd22262668b887121d4672af5a64b238f026099f1a2a1b322066c9ecfe9e0" +dependencies = [ + "bitflags 1.3.2", + "defmt-macros", +] + +[[package]] +name = "defmt-macros" +version = "0.3.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e3a9f309eff1f79b3ebdf252954d90ae440599c26c2c553fe87a2d17195f2dcb" +dependencies = [ + "defmt-parser", + "proc-macro-error", + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "defmt-parser" +version = "0.3.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ff4a5fefe330e8d7f31b16a318f9ce81000d8e35e69b93eae154d16d2278f70f" +dependencies = [ + "thiserror", +] + +[[package]] +name = "defmt-rtt" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bab697b3dbbc1750b7c8b821aa6f6e7f2480b47a99bc057a2ed7b170ebef0c51" +dependencies = [ + "critical-section", + "defmt", +] + +[[package]] +name = "document-features" +version = "0.2.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cb6969eaabd2421f8a2775cfd2471a2b634372b4a25d41e3bd647b79912850a0" +dependencies = [ + "litrs", +] + +[[package]] +name = "embassy-embedded-hal" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", + "embassy-futures", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "embedded-storage", + "embedded-storage-async", + "nb 1.1.0", +] + +[[package]] +name = "embassy-executor" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cortex-m", + "critical-section", + "defmt", + "document-features", + "embassy-executor-macros", + "embassy-time-driver", + "embassy-time-queue-driver", +] + +[[package]] +name = "embassy-executor-macros" +version = "0.5.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "darling", + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "embassy-futures" +version = "0.1.1" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" + +[[package]] +name = "embassy-hal-internal" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cortex-m", + "critical-section", + "defmt", + "num-traits", +] + +[[package]] +name = "embassy-net" +version = "0.4.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", + "document-features", + "embassy-net-driver", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embedded-io-async", + "embedded-nal-async", + "heapless", + "managed", + "smoltcp", +] + +[[package]] +name = "embassy-net-driver" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", +] + +[[package]] +name = "embassy-stm32" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "bit_field", + "bitflags 2.6.0", + "cfg-if", + "cortex-m", + "cortex-m-rt", + "critical-section", + "defmt", + "document-features", + "embassy-embedded-hal", + "embassy-futures", + "embassy-hal-internal", + "embassy-net-driver", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embassy-time-driver", + "embassy-usb-driver", + "embassy-usb-synopsys-otg", + "embedded-can", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "embedded-hal-nb", + "embedded-io", + "embedded-io-async", + "embedded-storage", + "embedded-storage-async", + "futures-util", + "nb 1.1.0", + "proc-macro2", + "quote", + "rand_core", + "sdio-host", + "static_assertions", + "stm32-fmc", + "stm32-metapac", + "vcell", + "volatile-register", +] + +[[package]] +name = "embassy-sync" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "embedded-io-async", + "futures-util", + "heapless", +] + +[[package]] +name = "embassy-sync" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy#9555259c57a07338792cfe0fdd363a59616a8062" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "embedded-io-async", + "futures-util", + "heapless", +] + +[[package]] +name = "embassy-time" +version = "0.3.2" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "document-features", + "embassy-time-driver", + "embassy-time-queue-driver", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "futures-util", + "heapless", +] + +[[package]] +name = "embassy-time-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "document-features", +] + +[[package]] +name = "embassy-time-queue-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" + +[[package]] +name = "embassy-usb-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", +] + +[[package]] +name = "embassy-usb-synopsys-otg" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "critical-section", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-usb-driver", +] + +[[package]] +name = "embedded-can" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "embedded-hal" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" +dependencies = [ + "nb 0.1.3", + "void", +] + +[[package]] +name = "embedded-hal" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "361a90feb7004eca4019fb28352a9465666b24f840f5c3cddf0ff13920590b89" + +[[package]] +name = "embedded-hal-async" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0c4c685bbef7fe13c3c6dd4da26841ed3980ef33e841cddfa15ce8a8fb3f1884" +dependencies = [ + "embedded-hal 1.0.0", +] + +[[package]] +name = "embedded-hal-nb" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fba4268c14288c828995299e59b12babdbe170f6c6d73731af1b4648142e8605" +dependencies = [ + "embedded-hal 1.0.0", + "nb 1.1.0", +] + +[[package]] +name = "embedded-io" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "edd0f118536f44f5ccd48bcb8b111bdc3de888b58c74639dfb034a357d0f206d" +dependencies = [ + "defmt", +] + +[[package]] +name = "embedded-io-async" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3ff09972d4073aa8c299395be75161d582e7629cd663171d62af73c8d50dba3f" +dependencies = [ + "defmt", + "embedded-io", +] + +[[package]] +name = "embedded-nal" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b8a943fad5ed3d3f8a00f1e80f6bba371f1e7f0df28ec38477535eb318dc19cc" +dependencies = [ + "nb 1.1.0", + "no-std-net", +] + +[[package]] +name = "embedded-nal-async" +version = "0.7.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72229137a4fc12d239b0b7f50f04b30790678da6d782a0f3f1909bf57ec4b759" +dependencies = [ + "embedded-io-async", + "embedded-nal", + "no-std-net", +] + +[[package]] +name = "embedded-storage" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a21dea9854beb860f3062d10228ce9b976da520a73474aed3171ec276bc0c032" + +[[package]] +name = "embedded-storage-async" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1763775e2323b7d5f0aa6090657f5e21cfa02ede71f5dc40eead06d64dcd15cc" +dependencies = [ + "embedded-storage", +] + +[[package]] +name = "fnv" +version = "1.0.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" + +[[package]] +name = "futures-core" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "05f29059c0c2090612e8d742178b0580d2dc940c837851ad723096f87af6663e" + +[[package]] +name = "futures-task" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f90f7dce0722e95104fcb095585910c0977252f286e354b5e3bd38902cd99988" + +[[package]] +name = "futures-util" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9fa08315bb612088cc391249efdc3bc77536f16c91f6cf495e6fbe85b20a4a81" +dependencies = [ + "futures-core", + "futures-task", + "pin-project-lite", + "pin-utils", +] + +[[package]] +name = "hash32" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "47d60b12902ba28e2730cd37e95b8c9223af2808df9e902d4df49588d1470606" +dependencies = [ + "byteorder", +] + +[[package]] +name = "heapless" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0bfb9eb618601c89945a70e254898da93b13be0388091d42117462b265bb3fad" +dependencies = [ + "defmt", + "hash32", + "serde", + "stable_deref_trait", +] + +[[package]] +name = "hyped_boards_stm32f767zi" +version = "0.1.0" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "critical-section", + "defmt", + "defmt-rtt", + "embassy-executor", + "embassy-futures", + "embassy-net", + "embassy-stm32", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy)", + "embassy-time", + "embedded-hal 0.2.7", + "embedded-storage", + "hyped_io", + "hyped_sensors", + "panic-probe", + "rand_core", + "static_cell", +] + +[[package]] +name = "hyped_core" +version = "0.1.0" +dependencies = [ + "defmt", + "embassy-net", + "embedded-io-async", + "heapless", + "rand_core", + "rust-mqtt", + "serde", +] + +[[package]] +name = "hyped_io" +version = "0.1.0" +dependencies = [ + "heapless", +] + +[[package]] +name = "hyped_sensors" +version = "0.1.0" +dependencies = [ + "heapless", + "hyped_core", + "hyped_io", +] + +[[package]] +name = "ident_case" +version = "1.0.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b9e0384b61958566e926dc50660321d12159025e767c18e043daf26b70104c39" + +[[package]] +name = "litrs" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4ce301924b7887e9d637144fdade93f9dfff9b60981d4ac161db09720d39aa5" + +[[package]] +name = "managed" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0ca88d725a0a943b096803bd34e73a4437208b6077654cc4ecb2947a5f91618d" + +[[package]] +name = "nb" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "nb" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" + +[[package]] +name = "no-std-net" +version = "0.6.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "43794a0ace135be66a25d3ae77d41b91615fb68ae937f904090203e81f755b65" + +[[package]] +name = "num-traits" +version = "0.2.19" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "071dfc062690e90b734c0b2273ce72ad0ffa95f0c74596bc250dcfd960262841" +dependencies = [ + "autocfg", +] + +[[package]] +name = "panic-probe" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4047d9235d1423d66cc97da7d07eddb54d4f154d6c13805c6d0793956f4f25b0" +dependencies = [ + "cortex-m", + "defmt", +] + +[[package]] +name = "pin-project-lite" +version = "0.2.14" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bda66fc9667c18cb2758a2ac84d1167245054bcf85d5d1aaa6923f45801bdd02" + +[[package]] +name = "pin-utils" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8b870d8c151b6f2fb93e84a13146138f05d02ed11c7e7c54f8826aaaf7c9f184" + +[[package]] +name = "portable-atomic" +version = "1.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cc9c68a3f6da06753e9335d63e27f6b9754dd1920d941135b7ea8224f141adb2" + +[[package]] +name = "proc-macro-error" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" +dependencies = [ + "proc-macro-error-attr", + "proc-macro2", + "quote", + "syn 1.0.109", + "version_check", +] + +[[package]] +name = "proc-macro-error-attr" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" +dependencies = [ + "proc-macro2", + "quote", + "version_check", +] + +[[package]] +name = "proc-macro2" +version = "1.0.87" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b3e4daa0dcf6feba26f985457cdf104d4b4256fc5a09547140f3631bb076b19a" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "quote" +version = "1.0.37" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b5b9d34b8991d19d98081b46eacdd8eb58c6f2b201139f7c5f643cc155a633af" +dependencies = [ + "proc-macro2", +] + +[[package]] +name = "rand_core" +version = "0.6.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" + +[[package]] +name = "rust-mqtt" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8f71160765f368fd9a84e0955e2ddb6d64ac9018fee1c5323354d6d08c816b40" +dependencies = [ + "defmt", + "embedded-io", + "embedded-io-async", + "heapless", + "rand_core", +] + +[[package]] +name = "rustc_version" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" +dependencies = [ + "semver", +] + +[[package]] +name = "sdio-host" +version = "0.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f93c025f9cfe4c388c328ece47d11a54a823da3b5ad0370b22d95ad47137f85a" + +[[package]] +name = "semver" +version = "0.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" +dependencies = [ + "semver-parser", +] + +[[package]] +name = "semver-parser" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" + +[[package]] +name = "serde" +version = "1.0.210" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c8e3592472072e6e22e0a54d5904d9febf8508f65fb8552499a1abc7d1078c3a" +dependencies = [ + "serde_derive", +] + +[[package]] +name = "serde_derive" +version = "1.0.210" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "243902eda00fad750862fc144cea25caca5e20d615af0a81bee94ca738f1df1f" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "smoltcp" +version = "0.11.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5a1a996951e50b5971a2c8c0fa05a381480d70a933064245c4a223ddc87ccc97" +dependencies = [ + "bitflags 1.3.2", + "byteorder", + "cfg-if", + "defmt", + "heapless", + "managed", +] + +[[package]] +name = "stable_deref_trait" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" + +[[package]] +name = "static_assertions" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" + +[[package]] +name = "static_cell" +version = "2.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d89b0684884a883431282db1e4343f34afc2ff6996fe1f4a1664519b66e14c1e" +dependencies = [ + "portable-atomic", +] + +[[package]] +name = "stm32-fmc" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c7f0639399e2307c2446c54d91d4f1596343a1e1d5cab605b9cce11d0ab3858c" +dependencies = [ + "embedded-hal 0.2.7", +] + +[[package]] +name = "stm32-metapac" +version = "15.0.0" +source = "git+https://github.com/embassy-rs/stm32-data-generated?tag=stm32-data-5ef354f3e49f790e47f5c818f243459742c9b83b#d94c7ea2bd05428ba9fd2b5a39edb8ed99f65daa" +dependencies = [ + "cortex-m", + "cortex-m-rt", +] + +[[package]] +name = "strsim" +version = "0.11.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7da8b5736845d9f2fcb837ea5d9e2628564b3b043a70948a3f0b778838c5fb4f" + +[[package]] +name = "syn" +version = "1.0.109" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "syn" +version = "2.0.79" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "89132cd0bf050864e1d38dc3bbc07a0eb8e7530af26344d3d2bbbef83499f590" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "thiserror" +version = "1.0.64" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d50af8abc119fb8bb6dbabcfa89656f46f84aa0ac7688088608076ad2b459a84" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.64" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "08904e7672f5eb876eaaf87e0ce17857500934f4981c4a0ab2b4aa98baac7fc3" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "unicode-ident" +version = "1.0.13" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e91b56cd4cadaeb79bbf1a5645f6b4f8dc5bde8834ad5894a8db35fda9efa1fe" + +[[package]] +name = "vcell" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" + +[[package]] +name = "version_check" +version = "0.9.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0b928f33d975fc6ad9f86c8f283853ad26bdd5b10b7f1542aa2fa15e2289105a" + +[[package]] +name = "void" +version = "1.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" + +[[package]] +name = "volatile-register" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de437e2a6208b014ab52972a27e59b33fa2920d3e00fe05026167a1c509d19cc" +dependencies = [ + "vcell", +] diff --git a/boards/stm32f767zi/Cargo.toml b/boards/stm32f767zi/Cargo.toml new file mode 100644 index 0000000..a2c008b --- /dev/null +++ b/boards/stm32f767zi/Cargo.toml @@ -0,0 +1,27 @@ +[package] +name = "hyped_boards_stm32f767zi" +version = "0.1.0" +edition = "2021" + +[dependencies] +embassy-stm32 = { version = "0.1.0", features = ["defmt", "stm32f767zi", "memory-x", "unstable-pac", "time-driver-any", "exti"] , git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-sync = { version = "0.6.0", features = ["defmt"], git = "https://github.com/embassy-rs/embassy"} +embassy-executor = { version = "0.6.0", features = ["task-arena-size-32768", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-time = { version = "0.3.1", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-net = { version = "0.4.0", features = ["defmt", "tcp", "dhcpv4", "medium-ethernet"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-futures = { version = "0.1.0", git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} + +defmt = "0.3" +defmt-rtt = "0.4" + +cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] } +cortex-m-rt = "0.7.0" +embedded-hal = "0.2.6" +panic-probe = { version = "0.3", features = ["print-defmt"] } +rand_core = "0.6.3" +critical-section = "1.1" +embedded-storage = "0.3.1" +static_cell = "2" + +hyped_io = { path = "../../lib/io" } +hyped_sensors = { path = "../../lib/sensors" } diff --git a/boards/stm32f767zi/build.rs b/boards/stm32f767zi/build.rs new file mode 100644 index 0000000..8cd32d7 --- /dev/null +++ b/boards/stm32f767zi/build.rs @@ -0,0 +1,5 @@ +fn main() { + println!("cargo:rustc-link-arg-bins=--nmagic"); + println!("cargo:rustc-link-arg-bins=-Tlink.x"); + println!("cargo:rustc-link-arg-bins=-Tdefmt.x"); +} diff --git a/boards/stm32f767zi/src/bin/keyence_test.rs b/boards/stm32f767zi/src/bin/keyence_test.rs new file mode 100644 index 0000000..1d876fb --- /dev/null +++ b/boards/stm32f767zi/src/bin/keyence_test.rs @@ -0,0 +1,16 @@ +#![no_std] +#![no_main] + +use embassy_executor::Spawner; +use embassy_time::{Duration, Timer}; +use hyped_boards_stm32f767zi::tasks::keyence::read_keyence; +use {defmt_rtt as _, panic_probe as _}; + +#[embassy_executor::main] +async fn main(spawner: Spawner) -> ! { + spawner.spawn(read_keyence()).unwrap(); + + loop { + Timer::after(Duration::from_secs(1)).await; + } +} diff --git a/boards/stm32f767zi/src/bin/temp_test.rs b/boards/stm32f767zi/src/bin/temp_test.rs new file mode 100644 index 0000000..a8ac34c --- /dev/null +++ b/boards/stm32f767zi/src/bin/temp_test.rs @@ -0,0 +1,16 @@ +#![no_std] +#![no_main] + +use embassy_executor::Spawner; +use embassy_time::{Duration, Timer}; +use hyped_boards_stm32f767zi::tasks::temperature::read_temp; +use {defmt_rtt as _, panic_probe as _}; + +#[embassy_executor::main] +async fn main(spawner: Spawner) -> ! { + spawner.spawn(read_temp()).unwrap(); + + loop { + Timer::after(Duration::from_secs(1)).await; + } +} diff --git a/boards/stm32f767zi/src/io.rs b/boards/stm32f767zi/src/io.rs new file mode 100644 index 0000000..c296886 --- /dev/null +++ b/boards/stm32f767zi/src/io.rs @@ -0,0 +1,2 @@ +pub mod gpio; +pub mod i2c; diff --git a/boards/stm32f767zi/src/io/gpio.rs b/boards/stm32f767zi/src/io/gpio.rs new file mode 100644 index 0000000..f95577c --- /dev/null +++ b/boards/stm32f767zi/src/io/gpio.rs @@ -0,0 +1,20 @@ +use embassy_stm32::gpio::Input; +use hyped_io::gpio::HypedGpioPin; + +/// A GPIO pin on the STM32L476RG. +pub struct Stm32f767ziGpio { + pin: Input<'static>, +} + +impl HypedGpioPin for Stm32f767ziGpio { + fn is_high(&mut self) -> bool { + self.pin.is_high() + } +} + +impl Stm32f767ziGpio { + /// Create a new instance of our GPIO implementation for the STM32L476RG + pub fn new(pin: Input<'static>) -> Self { + Self { pin } + } +} diff --git a/boards/stm32f767zi/src/io/i2c.rs b/boards/stm32f767zi/src/io/i2c.rs new file mode 100644 index 0000000..844212b --- /dev/null +++ b/boards/stm32f767zi/src/io/i2c.rs @@ -0,0 +1,51 @@ +use embassy_stm32::{i2c::I2c, mode::Blocking}; +use hyped_io::i2c::{HypedI2c, I2cError}; + +pub struct Stm32f767ziI2c<'d> { + i2c: I2c<'d, Blocking>, +} + +impl<'d> HypedI2c for Stm32f767ziI2c<'d> { + /// Read a byte from a register on a device + fn read_byte(&mut self, device_address: u8, register_address: u8) -> Option { + let mut read = [0]; + let result = + self.i2c + .blocking_write_read(device_address, [register_address].as_ref(), &mut read); + match result { + Ok(_) => Some(read[0]), + Err(_) => None, + } + } + + /// Write a byte to a register on a device + fn write_byte_to_register( + &mut self, + device_address: u8, + register_address: u8, + data: u8, + ) -> Result<(), I2cError> { + let result = self + .i2c + .blocking_write(device_address, [register_address, data].as_ref()); + match result { + Ok(_) => Ok(()), + Err(e) => Err(match e { + embassy_stm32::i2c::Error::Bus => I2cError::Bus, + embassy_stm32::i2c::Error::Arbitration => I2cError::Arbitration, + embassy_stm32::i2c::Error::Nack => I2cError::Nack, + embassy_stm32::i2c::Error::Timeout => I2cError::Timeout, + embassy_stm32::i2c::Error::Crc => I2cError::Crc, + embassy_stm32::i2c::Error::Overrun => I2cError::Overrun, + embassy_stm32::i2c::Error::ZeroLengthTransfer => I2cError::ZeroLengthTransfer, + }), + } + } +} + +impl<'d> Stm32f767ziI2c<'d> { + /// Create a new instance of our I2C implementation for the STM32L476RG + pub fn new(i2c: I2c<'d, Blocking>) -> Self { + Self { i2c } + } +} diff --git a/boards/stm32f767zi/src/lib.rs b/boards/stm32f767zi/src/lib.rs new file mode 100644 index 0000000..bf7c872 --- /dev/null +++ b/boards/stm32f767zi/src/lib.rs @@ -0,0 +1,4 @@ +#![no_std] + +pub mod io; +pub mod tasks; diff --git a/boards/stm32f767zi/src/tasks.rs b/boards/stm32f767zi/src/tasks.rs new file mode 100644 index 0000000..a557c36 --- /dev/null +++ b/boards/stm32f767zi/src/tasks.rs @@ -0,0 +1,2 @@ +pub mod keyence; +pub mod temperature; diff --git a/boards/stm32f767zi/src/tasks/keyence.rs b/boards/stm32f767zi/src/tasks/keyence.rs new file mode 100644 index 0000000..baaa447 --- /dev/null +++ b/boards/stm32f767zi/src/tasks/keyence.rs @@ -0,0 +1,17 @@ +use crate::io::gpio::Stm32f767ziGpio; +use embassy_stm32::gpio::{Input, Pull}; +use embassy_time::{Duration, Timer}; +use hyped_sensors::keyence::Keyence; + +/// Test task that just continually updates the stripe count from the Keyence sensor (or other GPIO pin input) +#[embassy_executor::task] +pub async fn read_keyence() -> ! { + let p = embassy_stm32::init(Default::default()); + let mut keyence = Keyence::new(Stm32f767ziGpio::new(Input::new(p.PC13, Pull::Down))); + + loop { + keyence.update_stripe_count(); + defmt::info!("Stripe count: {}", keyence.get_stripe_count()); + Timer::after(Duration::from_millis(100)).await; + } +} diff --git a/boards/stm32f767zi/src/tasks/temperature.rs b/boards/stm32f767zi/src/tasks/temperature.rs new file mode 100644 index 0000000..1d33940 --- /dev/null +++ b/boards/stm32f767zi/src/tasks/temperature.rs @@ -0,0 +1,45 @@ +use crate::io::i2c::Stm32f767ziI2c; +use defmt_rtt as _; +use embassy_stm32::i2c::I2c; +use embassy_stm32::time::Hertz; +use hyped_sensors::temperature::{Status, Temperature, TemperatureAddresses}; + +/// Test task that just reads the temperature from the sensor and prints it to the console +#[embassy_executor::task] +pub async fn read_temp() -> ! { + let p = embassy_stm32::init(Default::default()); + let i2c = I2c::new_blocking(p.I2C1, p.PB8, p.PB9, Hertz(100_000), Default::default()); + let hyped_i2c = Stm32f767ziI2c::new(i2c); + + let mut temperature_sensor = Temperature::new(hyped_i2c, TemperatureAddresses::Address3f) + .expect( + "Failed to create temperature sensor. Check the wiring and the I2C address of the sensor.", + ); + + loop { + match temperature_sensor.check_status() { + Status::TempOverUpperLimit => { + defmt::error!("Temperature is over the upper limit."); + } + Status::TempUnderLowerLimit => { + defmt::error!("Temperature is under the lower limit."); + } + Status::Busy => { + defmt::warn!("Temperature sensor is busy."); + } + Status::Unknown => { + panic!("Could not get the status of the temperature sensor.") + } + Status::Ok => {} + } + + match temperature_sensor.read() { + Some(temperature) => { + defmt::info!("Temperature: {:?}", temperature); + } + None => { + defmt::info!("Failed to read temperature."); + } + } + } +} diff --git a/boards/stm32l476rg/Cargo.toml b/boards/stm32l476rg/Cargo.toml index 3e87bbe..55a129f 100644 --- a/boards/stm32l476rg/Cargo.toml +++ b/boards/stm32l476rg/Cargo.toml @@ -25,15 +25,3 @@ static_cell = "2" hyped_io = { path = "../../lib/io" } hyped_sensors = { path = "../../lib/sensors" } - -[lib] -name = "hyped_boards_stm32l476rg" -path = "src/lib.rs" -test = false -doctest = false - -[[bin]] -name = "test_temp" -path = "src/bin/temp_test.rs" -test = false -doctest = false diff --git a/boards/stm32l476rg/src/io/gpio.rs b/boards/stm32l476rg/src/io/gpio.rs index 7326a4a..8bef3ad 100644 --- a/boards/stm32l476rg/src/io/gpio.rs +++ b/boards/stm32l476rg/src/io/gpio.rs @@ -1,12 +1,12 @@ use embassy_stm32::gpio::Input; -use hyped_io::gpio::GpioPin; +use hyped_io::gpio::HypedGpioPin; /// A GPIO pin on the STM32L476RG. pub struct Stm32l476rgGpio { pin: Input<'static>, } -impl GpioPin for Stm32l476rgGpio { +impl HypedGpioPin for Stm32l476rgGpio { fn is_high(&mut self) -> bool { self.pin.is_high() } diff --git a/lib/io/src/gpio.rs b/lib/io/src/gpio.rs index 0829cda..15e7707 100644 --- a/lib/io/src/gpio.rs +++ b/lib/io/src/gpio.rs @@ -1,5 +1,5 @@ /// Abstraction for a GPIO pin so that sensors can be tested with a mock GPIO pin -pub trait GpioPin { +pub trait HypedGpioPin { fn is_high(&mut self) -> bool; } @@ -12,7 +12,7 @@ pub mod mock_gpio { next_values: Vec, } - impl crate::gpio::GpioPin for MockGpio { + impl crate::gpio::HypedGpioPin for MockGpio { fn is_high(&mut self) -> bool { let next_value = self.next_values.pop().unwrap_or(self.current_value); self.current_value = next_value; diff --git a/lib/io/src/i2c.rs b/lib/io/src/i2c.rs index 8d636ce..451287e 100644 --- a/lib/io/src/i2c.rs +++ b/lib/io/src/i2c.rs @@ -1,8 +1,7 @@ -/// I2C trait used to abstract the I2C peripheral - +/// I2C errors that can occur +/// From: https://docs.embassy.dev/embassy-stm32/git/stm32g031c8/i2c/enum.Error.html #[derive(Debug)] pub enum I2cError { - // Error codes nased https://docs.embassy.dev/embassy-stm32/git/stm32g031c8/i2c/enum.Error.html Bus, Arbitration, Nack, @@ -13,6 +12,7 @@ pub enum I2cError { Unknown, } +/// I2C trait used to abstract the I2C peripheral pub trait HypedI2c { fn read_byte(&mut self, device_address: u8, register_address: u8) -> Option; fn write_byte_to_register( diff --git a/lib/sensors/src/keyence.rs b/lib/sensors/src/keyence.rs index 65b8f29..25d5f61 100644 --- a/lib/sensors/src/keyence.rs +++ b/lib/sensors/src/keyence.rs @@ -1,11 +1,11 @@ use hyped_core::types::DigitalSignal; -use hyped_io::gpio::GpioPin; +use hyped_io::gpio::HypedGpioPin; /// Keyence represents a Keyence sensor which keeps track of the number of stripes that have passed /// by the sensor. The Keyence sensor is connected to a GPIO pin which reads a high signal when a /// stripe is detected and a low signal when no stripe is detected. The stripe count is updated /// whenever the signal changes from low to high (positive edge). -pub struct Keyence { +pub struct Keyence { /// The number of stripes that have passed by the sensor. stripe_count: u32, /// The last signal that was read from the sensor. @@ -13,7 +13,7 @@ pub struct Keyence { gpio: T, } -impl Keyence { +impl Keyence { /// Creates a new Keyence sensor with an initial stripe count of 0 and a last signal of low. pub fn new(gpio: T) -> Keyence { Keyence { From 12a4da33b4b78af7655ad6d67f107026e4f4292e Mon Sep 17 00:00:00 2001 From: David Beechey Date: Mon, 28 Oct 2024 10:11:29 +0000 Subject: [PATCH 4/8] SNS - Create `MockI2c` (and temperature sensor tests) (#39) --- boards/stm32f767zi/src/tasks/temperature.rs | 4 +- boards/stm32l476rg/src/tasks/temperature.rs | 4 +- lib/io/src/i2c.rs | 53 +++++++++ lib/sensors/src/temperature.rs | 125 +++++++++++++++++++- 4 files changed, 176 insertions(+), 10 deletions(-) diff --git a/boards/stm32f767zi/src/tasks/temperature.rs b/boards/stm32f767zi/src/tasks/temperature.rs index 1d33940..c735dfd 100644 --- a/boards/stm32f767zi/src/tasks/temperature.rs +++ b/boards/stm32f767zi/src/tasks/temperature.rs @@ -9,9 +9,9 @@ use hyped_sensors::temperature::{Status, Temperature, TemperatureAddresses}; pub async fn read_temp() -> ! { let p = embassy_stm32::init(Default::default()); let i2c = I2c::new_blocking(p.I2C1, p.PB8, p.PB9, Hertz(100_000), Default::default()); - let hyped_i2c = Stm32f767ziI2c::new(i2c); + let mut hyped_i2c = Stm32f767ziI2c::new(i2c); - let mut temperature_sensor = Temperature::new(hyped_i2c, TemperatureAddresses::Address3f) + let mut temperature_sensor = Temperature::new(&mut hyped_i2c, TemperatureAddresses::Address3f) .expect( "Failed to create temperature sensor. Check the wiring and the I2C address of the sensor.", ); diff --git a/boards/stm32l476rg/src/tasks/temperature.rs b/boards/stm32l476rg/src/tasks/temperature.rs index 5eaee2c..d6e1068 100644 --- a/boards/stm32l476rg/src/tasks/temperature.rs +++ b/boards/stm32l476rg/src/tasks/temperature.rs @@ -9,9 +9,9 @@ use hyped_sensors::temperature::{Status, Temperature, TemperatureAddresses}; pub async fn read_temp() -> ! { let p = embassy_stm32::init(Default::default()); let i2c = I2c::new_blocking(p.I2C1, p.PB8, p.PB9, Hertz(100_000), Default::default()); - let hyped_i2c = Stm32l476rgI2c::new(i2c); + let mut hyped_i2c = Stm32l476rgI2c::new(i2c); - let mut temperature_sensor = Temperature::new(hyped_i2c, TemperatureAddresses::Address3f) + let mut temperature_sensor = Temperature::new(&mut hyped_i2c, TemperatureAddresses::Address3f) .expect( "Failed to create temperature sensor. Check the wiring and the I2C address of the sensor.", ); diff --git a/lib/io/src/i2c.rs b/lib/io/src/i2c.rs index 451287e..360a845 100644 --- a/lib/io/src/i2c.rs +++ b/lib/io/src/i2c.rs @@ -22,3 +22,56 @@ pub trait HypedI2c { data: u8, ) -> Result<(), I2cError>; } + +pub mod mock_i2c { + use heapless::FnvIndexMap; + + /// A fixed-size map of I2C values, indexed by device address and register address + type I2cValues = FnvIndexMap<(u8, u8), Option, 16>; + + /// A mock I2C instance which can be used for testing + pub struct MockI2c { + values: I2cValues, + writes: I2cValues, + } + + impl crate::i2c::HypedI2c for MockI2c { + /// Reads a byte by looking up the device address and register address in the map + fn read_byte(&mut self, device_address: u8, register_address: u8) -> Option { + self.values + .get(&(device_address, register_address)) + .copied() + .unwrap() + } + + /// Writes a byte to the map so that it can be read later to check the value + fn write_byte_to_register( + &mut self, + device_address: u8, + register_address: u8, + data: u8, + ) -> Result<(), super::I2cError> { + match self + .writes + .insert((device_address, register_address), Some(data)) + { + Ok(_) => Ok(()), + Err(_) => Err(super::I2cError::Unknown), + } + } + } + + impl MockI2c { + pub fn new(values: I2cValues) -> MockI2c { + MockI2c { + values, + writes: I2cValues::new(), + } + } + + /// Returns a reference to the I2C values map + pub fn get_writes(&self) -> &I2cValues { + &self.writes + } + } +} diff --git a/lib/sensors/src/temperature.rs b/lib/sensors/src/temperature.rs index a76da53..322ea89 100644 --- a/lib/sensors/src/temperature.rs +++ b/lib/sensors/src/temperature.rs @@ -7,14 +7,17 @@ use hyped_io::i2c::{HypedI2c, I2cError}; /// The temperature is read from the sensor and converted to a floating point value in degrees Celsius. /// /// Data sheet: https://www.st.com/resource/en/datasheet/stts22h.pdf -pub struct Temperature { - i2c: T, +pub struct Temperature<'a, T: HypedI2c + 'a> { + i2c: &'a mut T, device_address: u8, } -impl Temperature { +impl<'a, T: HypedI2c> Temperature<'a, T> { /// Create a new instance of the temperature sensor and attempt to configure it - pub fn new(mut i2c: T, device_address: TemperatureAddresses) -> Result { + pub fn new( + i2c: &'a mut T, + device_address: TemperatureAddresses, + ) -> Result { // Set up the temperature sensor by sending the configuration settings to the STTS22H_CTRL register let device_address = device_address as u8; match i2c.write_byte_to_register(device_address, STTS22H_CTRL, STTS22H_CONFIG_SETTINGS) { @@ -45,9 +48,13 @@ impl Temperature { }; let combined: f32 = ((temperature_high_byte as u16) << 8 | temperature_low_byte as u16) as f32; - let temperature = combined * STTS22H_TEMP_SCALING_FACTOR; - Some(temperature) + if combined >= TWO_POWER_15 { + // Convert the temperature to a negative value + return Some((combined - TWO_POWER_16) * STTS22H_TEMP_SCALING_FACTOR); + } + + Some(combined * STTS22H_TEMP_SCALING_FACTOR) } /// Check the status of the temperature sensor @@ -77,6 +84,7 @@ pub enum TemperatureError { } /// Represents the possible statuses of the temperature sensor +#[derive(Debug, PartialEq)] pub enum Status { Busy, TempOverUpperLimit, @@ -113,3 +121,108 @@ const STTS22H_CONFIG_SETTINGS: u8 = 0x3c; // Scaling factor to convert the temperature from the sensor to degrees Celsius const STTS22H_TEMP_SCALING_FACTOR: f32 = 0.01; +const TWO_POWER_15: f32 = 32768.0; +const TWO_POWER_16: f32 = 65536.0; + +#[cfg(test)] +mod tests { + use super::*; + use heapless::FnvIndexMap; + use hyped_io::i2c::mock_i2c::MockI2c; + + #[test] + fn test_write_config() { + let i2c_values = FnvIndexMap::new(); + let mut i2c = MockI2c::new(i2c_values); + let _ = Temperature::new(&mut i2c, TemperatureAddresses::Address3f); + assert_eq!( + i2c.get_writes() + .get(&(TemperatureAddresses::Address3f as u8, STTS22H_CTRL)), + Some(&Some(STTS22H_CONFIG_SETTINGS)) + ); + } + + #[test] + fn test_temperature_read_0() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_H), + Some(0x00), + ); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_L), + Some(0x00), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.read(), Some(0.0)); + } + + #[test] + fn test_temperature_read_25() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_H), + Some(0x09), + ); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_L), + Some(0xc4), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.read(), Some(25.0)); + } + + #[test] + fn test_temperature_read_minus_10() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_H), + Some(0xfc), + ); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_DATA_TEMP_L), + Some(0x18), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.read(), Some(-10.0)); + } + + #[test] + fn test_temperature_status_busy() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_STATUS), + Some(STTS22H_STATUS_BUSY), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.check_status(), Status::Busy); + } + + #[test] + fn test_temperature_status_temp_over_upper_limit() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_STATUS), + Some(STTS22H_TEMP_OVER_UPPER_LIMIT), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.check_status(), Status::TempOverUpperLimit); + } + + #[test] + fn test_temperature_status_temp_under_lower_limit() { + let mut i2c_values = FnvIndexMap::new(); + let _ = i2c_values.insert( + (TemperatureAddresses::Address3f as u8, STTS22H_STATUS), + Some(STTS22H_TEMP_UNDER_LOWER_LIMIT), + ); + let mut i2c = MockI2c::new(i2c_values); + let mut temperature = Temperature::new(&mut i2c, TemperatureAddresses::Address3f).unwrap(); + assert_eq!(temperature.check_status(), Status::TempUnderLowerLimit); + } +} From dd8a72780deefaefafa5e8286dba29da4a8a7810 Mon Sep 17 00:00:00 2001 From: Joao Pedro Bastos <86593844+jpfbastos@users.noreply.github.com> Date: Thu, 31 Oct 2024 20:33:16 +0000 Subject: [PATCH 5/8] MLC - Create files (#42) Co-authored-by: David Beechey --- Cargo.lock | 4 ++++ lib/levitation/Cargo.toml | 4 ++++ lib/levitation/src/control.rs | 1 + lib/levitation/src/lib.rs | 3 +++ lib/levitation/src/pid.rs | 2 ++ lib/levitation/src/pid/current.rs | 1 + lib/levitation/src/pid/height.rs | 1 + lib/levitation/src/pwm.rs | 1 + 8 files changed, 17 insertions(+) create mode 100644 lib/levitation/Cargo.toml create mode 100644 lib/levitation/src/control.rs create mode 100644 lib/levitation/src/lib.rs create mode 100644 lib/levitation/src/pid.rs create mode 100644 lib/levitation/src/pid/current.rs create mode 100644 lib/levitation/src/pid/height.rs create mode 100644 lib/levitation/src/pwm.rs diff --git a/Cargo.lock b/Cargo.lock index f06f0c9..acd32e1 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -307,6 +307,10 @@ dependencies = [ "heapless", ] +[[package]] +name = "hyped_levitation" +version = "0.1.0" + [[package]] name = "hyped_localisation" version = "0.1.0" diff --git a/lib/levitation/Cargo.toml b/lib/levitation/Cargo.toml new file mode 100644 index 0000000..2d8ac20 --- /dev/null +++ b/lib/levitation/Cargo.toml @@ -0,0 +1,4 @@ +[package] +name = "hyped_levitation" +version = "0.1.0" +edition = "2021" diff --git a/lib/levitation/src/control.rs b/lib/levitation/src/control.rs new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/lib/levitation/src/control.rs @@ -0,0 +1 @@ + diff --git a/lib/levitation/src/lib.rs b/lib/levitation/src/lib.rs new file mode 100644 index 0000000..f16f322 --- /dev/null +++ b/lib/levitation/src/lib.rs @@ -0,0 +1,3 @@ +pub mod control; +pub mod pid; +pub mod pwm; diff --git a/lib/levitation/src/pid.rs b/lib/levitation/src/pid.rs new file mode 100644 index 0000000..73fae03 --- /dev/null +++ b/lib/levitation/src/pid.rs @@ -0,0 +1,2 @@ +pub mod current; +pub mod height; diff --git a/lib/levitation/src/pid/current.rs b/lib/levitation/src/pid/current.rs new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/lib/levitation/src/pid/current.rs @@ -0,0 +1 @@ + diff --git a/lib/levitation/src/pid/height.rs b/lib/levitation/src/pid/height.rs new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/lib/levitation/src/pid/height.rs @@ -0,0 +1 @@ + diff --git a/lib/levitation/src/pwm.rs b/lib/levitation/src/pwm.rs new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/lib/levitation/src/pwm.rs @@ -0,0 +1 @@ + From b44a9010fa19f75645c6e3f4322fa1d4e49d0127 Mon Sep 17 00:00:00 2001 From: Kshitij Sharma Date: Sun, 3 Nov 2024 11:54:08 +0000 Subject: [PATCH 6/8] INFRA - Telemetry Board (HYPE-17) (#5) Co-authored-by: David Beechey Co-authored-by: platinumxy <83834735+platinumxy@users.noreply.github.com> --- Cargo.lock | 44 +- Cargo.toml | 3 +- boards/stm32h743zi/.cargo/config.toml | 9 + boards/stm32h743zi/Cargo.lock | 970 ++++++++++++++++++++++ boards/stm32h743zi/Cargo.toml | 32 + boards/stm32h743zi/build.rs | 5 + boards/stm32h743zi/src/bin/telemetry.rs | 125 +++ boards/stm32h743zi/src/config.rs | 9 + boards/stm32h743zi/src/lib.rs | 5 + boards/stm32h743zi/src/log.rs | 21 + boards/stm32h743zi/src/tasks.rs | 3 + boards/stm32h743zi/src/tasks/button.rs | 38 + boards/stm32h743zi/src/tasks/heartbeat.rs | 22 + boards/stm32h743zi/src/tasks/mqtt.rs | 150 ++++ lib/core/Cargo.lock | 234 ++++++ lib/core/src/mqtt.rs | 22 +- lib/core/src/mqtt_topics.rs | 45 +- 17 files changed, 1683 insertions(+), 54 deletions(-) create mode 100644 boards/stm32h743zi/.cargo/config.toml create mode 100644 boards/stm32h743zi/Cargo.lock create mode 100644 boards/stm32h743zi/Cargo.toml create mode 100644 boards/stm32h743zi/build.rs create mode 100644 boards/stm32h743zi/src/bin/telemetry.rs create mode 100644 boards/stm32h743zi/src/config.rs create mode 100644 boards/stm32h743zi/src/lib.rs create mode 100644 boards/stm32h743zi/src/log.rs create mode 100644 boards/stm32h743zi/src/tasks.rs create mode 100644 boards/stm32h743zi/src/tasks/button.rs create mode 100644 boards/stm32h743zi/src/tasks/heartbeat.rs create mode 100644 boards/stm32h743zi/src/tasks/mqtt.rs create mode 100644 lib/core/Cargo.lock diff --git a/Cargo.lock b/Cargo.lock index acd32e1..6db5714 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -4,9 +4,9 @@ version = 3 [[package]] name = "anyhow" -version = "1.0.89" +version = "1.0.91" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "86fdf8605db99b54d3cd748a44c6d04df638eb5dafb219b135d0149bd0db01f6" +checksum = "c042108f3ed77fd83760a5fd79b53be043192bb3b9dba91d8c574c0ada7850c8" [[package]] name = "approx" @@ -49,9 +49,9 @@ checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" [[package]] name = "critical-section" -version = "1.1.3" +version = "1.2.0" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f64009896348fc5af4222e9cf7d7d82a95a256c634ebcf61c53e4ea461422242" +checksum = "790eea4361631c5e7d22598ecd5723ff611904e3344ce8720784c93e3d83d40b" [[package]] name = "defmt" @@ -73,7 +73,7 @@ dependencies = [ "proc-macro-error", "proc-macro2", "quote", - "syn 2.0.79", + "syn 2.0.82", ] [[package]] @@ -383,9 +383,9 @@ checksum = "78ca9ab1a0babb1e7d5695e3530886289c18cf2f87ec19a575a0abdce112e3a3" [[package]] name = "nalgebra" -version = "0.33.0" +version = "0.33.1" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3c4b5f057b303842cf3262c27e465f4c303572e7f6b0648f60e16248ac3397f4" +checksum = "3bf139e93ad757869338ad85239cb1d6c067b23b94e5846e637ca6328ee4be60" dependencies = [ "approx", "matrixmultiply", @@ -405,7 +405,7 @@ checksum = "254a5372af8fc138e36684761d3c0cdb758a4410e938babcff1c860ce14ddbfc" dependencies = [ "proc-macro2", "quote", - "syn 2.0.79", + "syn 2.0.82", ] [[package]] @@ -521,9 +521,9 @@ dependencies = [ [[package]] name = "proc-macro2" -version = "1.0.87" +version = "1.0.89" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b3e4daa0dcf6feba26f985457cdf104d4b4256fc5a09547140f3631bb076b19a" +checksum = "f139b0662de085916d1fb67d2b4169d1addddda1919e696f3252b740b629986e" dependencies = [ "unicode-ident", ] @@ -579,22 +579,22 @@ dependencies = [ [[package]] name = "serde" -version = "1.0.210" +version = "1.0.213" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c8e3592472072e6e22e0a54d5904d9febf8508f65fb8552499a1abc7d1078c3a" +checksum = "3ea7893ff5e2466df8d720bb615088341b295f849602c6956047f8f80f0e9bc1" dependencies = [ "serde_derive", ] [[package]] name = "serde_derive" -version = "1.0.210" +version = "1.0.213" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "243902eda00fad750862fc144cea25caca5e20d615af0a81bee94ca738f1df1f" +checksum = "7e85ad2009c50b58e87caa8cd6dac16bdf511bbfb7af6c33df902396aa480fa5" dependencies = [ "proc-macro2", "quote", - "syn 2.0.79", + "syn 2.0.82", ] [[package]] @@ -657,9 +657,9 @@ dependencies = [ [[package]] name = "syn" -version = "2.0.79" +version = "2.0.82" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "89132cd0bf050864e1d38dc3bbc07a0eb8e7530af26344d3d2bbbef83499f590" +checksum = "83540f837a8afc019423a8edb95b52a8effe46957ee402287f4292fae35be021" dependencies = [ "proc-macro2", "quote", @@ -668,22 +668,22 @@ dependencies = [ [[package]] name = "thiserror" -version = "1.0.64" +version = "1.0.65" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d50af8abc119fb8bb6dbabcfa89656f46f84aa0ac7688088608076ad2b459a84" +checksum = "5d11abd9594d9b38965ef50805c5e469ca9cc6f197f883f717e0269a3057b3d5" dependencies = [ "thiserror-impl", ] [[package]] name = "thiserror-impl" -version = "1.0.64" +version = "1.0.65" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "08904e7672f5eb876eaaf87e0ce17857500934f4981c4a0ab2b4aa98baac7fc3" +checksum = "ae71770322cbd277e69d762a16c444af02aa0575ac0d174f0b9562d3b37f8602" dependencies = [ "proc-macro2", "quote", - "syn 2.0.79", + "syn 2.0.82", ] [[package]] diff --git a/Cargo.toml b/Cargo.toml index 158ab8e..380df44 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,10 +1,11 @@ [workspace] members = [ "config", - "lib/*", + "lib/*" ] exclude = [ "boards/stm32l476rg", + "boards/stm32h743zi", "boards/stm32f767zi", ] resolver = "2" \ No newline at end of file diff --git a/boards/stm32h743zi/.cargo/config.toml b/boards/stm32h743zi/.cargo/config.toml new file mode 100644 index 0000000..53a6a11 --- /dev/null +++ b/boards/stm32h743zi/.cargo/config.toml @@ -0,0 +1,9 @@ +[target.'cfg(all(target_arch = "arm", target_os = "none"))'] +# replace STM32F429ZITx with your chip as listed in `probe-rs chip list` +runner = "probe-rs run --chip STM32H743ZITx" + +[build] +target = "thumbv7em-none-eabihf" + +[env] +DEFMT_LOG = "debug,smoltcp=info" diff --git a/boards/stm32h743zi/Cargo.lock b/boards/stm32h743zi/Cargo.lock new file mode 100644 index 0000000..737efd4 --- /dev/null +++ b/boards/stm32h743zi/Cargo.lock @@ -0,0 +1,970 @@ +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "as-slice" +version = "0.1.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "45403b49e3954a4b8428a0ac21a4b7afadccf92bfd96273f1a58cd4812496ae0" +dependencies = [ + "generic-array 0.12.4", + "generic-array 0.13.3", + "generic-array 0.14.7", + "stable_deref_trait", +] + +[[package]] +name = "autocfg" +version = "1.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ace50bade8e6234aa140d9a2f552bbee1db4d353f69b8217bc503490fc1a9f26" + +[[package]] +name = "bare-metal" +version = "0.2.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" +dependencies = [ + "rustc_version", +] + +[[package]] +name = "bit_field" +version = "0.10.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dc827186963e592360843fb5ba4b973e145841266c1357f7180c43526f2e5b61" + +[[package]] +name = "bitfield" +version = "0.13.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" + +[[package]] +name = "bitflags" +version = "1.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" + +[[package]] +name = "bitflags" +version = "2.6.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b048fb63fd8b5923fc5aa7b340d8e156aec7ec02f0c78fa8a6ddc2613f6f71de" + +[[package]] +name = "byteorder" +version = "1.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1fd0f2584146f6f2ef48085050886acf353beff7305ebd1ae69500e27c67f64b" + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "cortex-m" +version = "0.7.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" +dependencies = [ + "bare-metal", + "bitfield", + "critical-section", + "embedded-hal 0.2.7", + "volatile-register", +] + +[[package]] +name = "cortex-m-rt" +version = "0.7.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" +dependencies = [ + "cortex-m-rt-macros", +] + +[[package]] +name = "cortex-m-rt-macros" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" +dependencies = [ + "proc-macro2", + "quote", + "syn 1.0.109", +] + +[[package]] +name = "critical-section" +version = "1.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f64009896348fc5af4222e9cf7d7d82a95a256c634ebcf61c53e4ea461422242" + +[[package]] +name = "darling" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6f63b86c8a8826a49b8c21f08a2d07338eec8d900540f8630dc76284be802989" +dependencies = [ + "darling_core", + "darling_macro", +] + +[[package]] +name = "darling_core" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "95133861a8032aaea082871032f5815eb9e98cef03fa916ab4500513994df9e5" +dependencies = [ + "fnv", + "ident_case", + "proc-macro2", + "quote", + "strsim", + "syn 2.0.79", +] + +[[package]] +name = "darling_macro" +version = "0.20.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d336a2a514f6ccccaa3e09b02d41d35330c07ddf03a62165fcec10bb561c7806" +dependencies = [ + "darling_core", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "defmt" +version = "0.3.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a99dd22262668b887121d4672af5a64b238f026099f1a2a1b322066c9ecfe9e0" +dependencies = [ + "bitflags 1.3.2", + "defmt-macros", +] + +[[package]] +name = "defmt-macros" +version = "0.3.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e3a9f309eff1f79b3ebdf252954d90ae440599c26c2c553fe87a2d17195f2dcb" +dependencies = [ + "defmt-parser", + "proc-macro-error", + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "defmt-parser" +version = "0.3.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ff4a5fefe330e8d7f31b16a318f9ce81000d8e35e69b93eae154d16d2278f70f" +dependencies = [ + "thiserror", +] + +[[package]] +name = "defmt-rtt" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bab697b3dbbc1750b7c8b821aa6f6e7f2480b47a99bc057a2ed7b170ebef0c51" +dependencies = [ + "critical-section", + "defmt", +] + +[[package]] +name = "document-features" +version = "0.2.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cb6969eaabd2421f8a2775cfd2471a2b634372b4a25d41e3bd647b79912850a0" +dependencies = [ + "litrs", +] + +[[package]] +name = "embassy-embedded-hal" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", + "embassy-futures", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "embedded-storage", + "embedded-storage-async", + "nb 1.1.0", +] + +[[package]] +name = "embassy-executor" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cortex-m", + "critical-section", + "defmt", + "document-features", + "embassy-executor-macros", + "embassy-time-driver", + "embassy-time-queue-driver", +] + +[[package]] +name = "embassy-executor-macros" +version = "0.5.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "darling", + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "embassy-futures" +version = "0.1.1" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" + +[[package]] +name = "embassy-hal-internal" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cortex-m", + "critical-section", + "defmt", + "num-traits", +] + +[[package]] +name = "embassy-net" +version = "0.4.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", + "document-features", + "embassy-net-driver", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embedded-io-async", + "embedded-nal-async", + "heapless 0.8.0", + "managed", + "smoltcp", +] + +[[package]] +name = "embassy-net-driver" +version = "0.2.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", +] + +[[package]] +name = "embassy-stm32" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "bit_field", + "bitflags 2.6.0", + "cfg-if", + "cortex-m", + "cortex-m-rt", + "critical-section", + "defmt", + "document-features", + "embassy-embedded-hal", + "embassy-futures", + "embassy-hal-internal", + "embassy-net-driver", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-time", + "embassy-time-driver", + "embassy-usb-driver", + "embassy-usb-synopsys-otg", + "embedded-can", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "embedded-hal-nb", + "embedded-io", + "embedded-io-async", + "embedded-storage", + "embedded-storage-async", + "futures-util", + "nb 1.1.0", + "proc-macro2", + "quote", + "rand_core", + "sdio-host", + "static_assertions", + "stm32-fmc", + "stm32-metapac", + "vcell", + "volatile-register", +] + +[[package]] +name = "embassy-sync" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "embedded-io-async", + "futures-util", + "heapless 0.8.0", +] + +[[package]] +name = "embassy-sync" +version = "0.6.0" +source = "git+https://github.com/embassy-rs/embassy#9555259c57a07338792cfe0fdd363a59616a8062" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "embedded-io-async", + "futures-util", + "heapless 0.8.0", +] + +[[package]] +name = "embassy-time" +version = "0.3.2" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "cfg-if", + "critical-section", + "defmt", + "document-features", + "embassy-time-driver", + "embassy-time-queue-driver", + "embedded-hal 0.2.7", + "embedded-hal 1.0.0", + "embedded-hal-async", + "futures-util", + "heapless 0.8.0", +] + +[[package]] +name = "embassy-time-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "document-features", +] + +[[package]] +name = "embassy-time-queue-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" + +[[package]] +name = "embassy-usb-driver" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "defmt", +] + +[[package]] +name = "embassy-usb-synopsys-otg" +version = "0.1.0" +source = "git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7#1c466b81e6af6b34b1f706318cc0870a459550b7" +dependencies = [ + "critical-section", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy?rev=1c466b81e6af6b34b1f706318cc0870a459550b7)", + "embassy-usb-driver", +] + +[[package]] +name = "embedded-can" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "embedded-hal" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" +dependencies = [ + "nb 0.1.3", + "void", +] + +[[package]] +name = "embedded-hal" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "361a90feb7004eca4019fb28352a9465666b24f840f5c3cddf0ff13920590b89" + +[[package]] +name = "embedded-hal-async" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0c4c685bbef7fe13c3c6dd4da26841ed3980ef33e841cddfa15ce8a8fb3f1884" +dependencies = [ + "embedded-hal 1.0.0", +] + +[[package]] +name = "embedded-hal-nb" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fba4268c14288c828995299e59b12babdbe170f6c6d73731af1b4648142e8605" +dependencies = [ + "embedded-hal 1.0.0", + "nb 1.1.0", +] + +[[package]] +name = "embedded-io" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "edd0f118536f44f5ccd48bcb8b111bdc3de888b58c74639dfb034a357d0f206d" +dependencies = [ + "defmt", +] + +[[package]] +name = "embedded-io-async" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3ff09972d4073aa8c299395be75161d582e7629cd663171d62af73c8d50dba3f" +dependencies = [ + "defmt", + "embedded-io", +] + +[[package]] +name = "embedded-nal" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b8a943fad5ed3d3f8a00f1e80f6bba371f1e7f0df28ec38477535eb318dc19cc" +dependencies = [ + "nb 1.1.0", + "no-std-net", +] + +[[package]] +name = "embedded-nal-async" +version = "0.7.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72229137a4fc12d239b0b7f50f04b30790678da6d782a0f3f1909bf57ec4b759" +dependencies = [ + "embedded-io-async", + "embedded-nal", + "no-std-net", +] + +[[package]] +name = "embedded-storage" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a21dea9854beb860f3062d10228ce9b976da520a73474aed3171ec276bc0c032" + +[[package]] +name = "embedded-storage-async" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1763775e2323b7d5f0aa6090657f5e21cfa02ede71f5dc40eead06d64dcd15cc" +dependencies = [ + "embedded-storage", +] + +[[package]] +name = "fnv" +version = "1.0.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" + +[[package]] +name = "futures-core" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "05f29059c0c2090612e8d742178b0580d2dc940c837851ad723096f87af6663e" + +[[package]] +name = "futures-task" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f90f7dce0722e95104fcb095585910c0977252f286e354b5e3bd38902cd99988" + +[[package]] +name = "futures-util" +version = "0.3.31" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9fa08315bb612088cc391249efdc3bc77536f16c91f6cf495e6fbe85b20a4a81" +dependencies = [ + "futures-core", + "futures-task", + "pin-project-lite", + "pin-utils", +] + +[[package]] +name = "generic-array" +version = "0.12.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ffdf9f34f1447443d37393cc6c2b8313aebddcd96906caf34e54c68d8e57d7bd" +dependencies = [ + "typenum", +] + +[[package]] +name = "generic-array" +version = "0.13.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f797e67af32588215eaaab8327027ee8e71b9dd0b2b26996aedf20c030fce309" +dependencies = [ + "typenum", +] + +[[package]] +name = "generic-array" +version = "0.14.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "85649ca51fd72272d7821adaf274ad91c288277713d9c18820d8499a7ff69e9a" +dependencies = [ + "typenum", + "version_check", +] + +[[package]] +name = "hash32" +version = "0.1.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d4041af86e63ac4298ce40e5cca669066e75b6f1aa3390fe2561ffa5e1d9f4cc" +dependencies = [ + "byteorder", +] + +[[package]] +name = "hash32" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "47d60b12902ba28e2730cd37e95b8c9223af2808df9e902d4df49588d1470606" +dependencies = [ + "byteorder", +] + +[[package]] +name = "heapless" +version = "0.5.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "74911a68a1658cfcfb61bc0ccfbd536e3b6e906f8c2f7883ee50157e3e2184f1" +dependencies = [ + "as-slice", + "generic-array 0.13.3", + "hash32 0.1.1", + "stable_deref_trait", +] + +[[package]] +name = "heapless" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0bfb9eb618601c89945a70e254898da93b13be0388091d42117462b265bb3fad" +dependencies = [ + "defmt", + "hash32 0.3.1", + "serde", + "stable_deref_trait", +] + +[[package]] +name = "hyped_boards_stm32h743zi" +version = "0.1.0" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "critical-section", + "defmt", + "defmt-rtt", + "embassy-executor", + "embassy-futures", + "embassy-net", + "embassy-stm32", + "embassy-sync 0.6.0 (git+https://github.com/embassy-rs/embassy)", + "embassy-time", + "embedded-hal 0.2.7", + "embedded-storage", + "heapless 0.8.0", + "hyped_core", + "panic-probe", + "rand_core", + "rust-mqtt", + "serde", + "serde-json-core", + "static_cell", + "typenum", +] + +[[package]] +name = "hyped_core" +version = "0.1.0" +dependencies = [ + "defmt", + "embassy-net", + "embedded-io-async", + "heapless 0.8.0", + "rand_core", + "rust-mqtt", + "serde", +] + +[[package]] +name = "ident_case" +version = "1.0.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b9e0384b61958566e926dc50660321d12159025e767c18e043daf26b70104c39" + +[[package]] +name = "litrs" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4ce301924b7887e9d637144fdade93f9dfff9b60981d4ac161db09720d39aa5" + +[[package]] +name = "managed" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0ca88d725a0a943b096803bd34e73a4437208b6077654cc4ecb2947a5f91618d" + +[[package]] +name = "nb" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "nb" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" + +[[package]] +name = "no-std-net" +version = "0.6.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "43794a0ace135be66a25d3ae77d41b91615fb68ae937f904090203e81f755b65" + +[[package]] +name = "num-traits" +version = "0.2.19" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "071dfc062690e90b734c0b2273ce72ad0ffa95f0c74596bc250dcfd960262841" +dependencies = [ + "autocfg", +] + +[[package]] +name = "panic-probe" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4047d9235d1423d66cc97da7d07eddb54d4f154d6c13805c6d0793956f4f25b0" +dependencies = [ + "cortex-m", + "defmt", +] + +[[package]] +name = "pin-project-lite" +version = "0.2.14" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bda66fc9667c18cb2758a2ac84d1167245054bcf85d5d1aaa6923f45801bdd02" + +[[package]] +name = "pin-utils" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8b870d8c151b6f2fb93e84a13146138f05d02ed11c7e7c54f8826aaaf7c9f184" + +[[package]] +name = "portable-atomic" +version = "1.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cc9c68a3f6da06753e9335d63e27f6b9754dd1920d941135b7ea8224f141adb2" + +[[package]] +name = "proc-macro-error" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" +dependencies = [ + "proc-macro-error-attr", + "proc-macro2", + "quote", + "syn 1.0.109", + "version_check", +] + +[[package]] +name = "proc-macro-error-attr" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" +dependencies = [ + "proc-macro2", + "quote", + "version_check", +] + +[[package]] +name = "proc-macro2" +version = "1.0.87" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b3e4daa0dcf6feba26f985457cdf104d4b4256fc5a09547140f3631bb076b19a" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "quote" +version = "1.0.37" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b5b9d34b8991d19d98081b46eacdd8eb58c6f2b201139f7c5f643cc155a633af" +dependencies = [ + "proc-macro2", +] + +[[package]] +name = "rand_core" +version = "0.6.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" + +[[package]] +name = "rust-mqtt" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8f71160765f368fd9a84e0955e2ddb6d64ac9018fee1c5323354d6d08c816b40" +dependencies = [ + "defmt", + "embedded-io", + "embedded-io-async", + "heapless 0.8.0", + "rand_core", +] + +[[package]] +name = "rustc_version" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" +dependencies = [ + "semver", +] + +[[package]] +name = "sdio-host" +version = "0.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f93c025f9cfe4c388c328ece47d11a54a823da3b5ad0370b22d95ad47137f85a" + +[[package]] +name = "semver" +version = "0.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" +dependencies = [ + "semver-parser", +] + +[[package]] +name = "semver-parser" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" + +[[package]] +name = "serde" +version = "1.0.210" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c8e3592472072e6e22e0a54d5904d9febf8508f65fb8552499a1abc7d1078c3a" +dependencies = [ + "serde_derive", +] + +[[package]] +name = "serde-json-core" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cbf406405ada9ef326ca78677324ac66994ff348fc48a16030be08caeed29825" +dependencies = [ + "heapless 0.5.6", + "serde", +] + +[[package]] +name = "serde_derive" +version = "1.0.210" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "243902eda00fad750862fc144cea25caca5e20d615af0a81bee94ca738f1df1f" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "smoltcp" +version = "0.11.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5a1a996951e50b5971a2c8c0fa05a381480d70a933064245c4a223ddc87ccc97" +dependencies = [ + "bitflags 1.3.2", + "byteorder", + "cfg-if", + "defmt", + "heapless 0.8.0", + "managed", +] + +[[package]] +name = "stable_deref_trait" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" + +[[package]] +name = "static_assertions" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" + +[[package]] +name = "static_cell" +version = "2.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d89b0684884a883431282db1e4343f34afc2ff6996fe1f4a1664519b66e14c1e" +dependencies = [ + "portable-atomic", +] + +[[package]] +name = "stm32-fmc" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c7f0639399e2307c2446c54d91d4f1596343a1e1d5cab605b9cce11d0ab3858c" +dependencies = [ + "embedded-hal 0.2.7", +] + +[[package]] +name = "stm32-metapac" +version = "15.0.0" +source = "git+https://github.com/embassy-rs/stm32-data-generated?tag=stm32-data-5ef354f3e49f790e47f5c818f243459742c9b83b#d94c7ea2bd05428ba9fd2b5a39edb8ed99f65daa" +dependencies = [ + "cortex-m", + "cortex-m-rt", +] + +[[package]] +name = "strsim" +version = "0.11.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7da8b5736845d9f2fcb837ea5d9e2628564b3b043a70948a3f0b778838c5fb4f" + +[[package]] +name = "syn" +version = "1.0.109" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "syn" +version = "2.0.79" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "89132cd0bf050864e1d38dc3bbc07a0eb8e7530af26344d3d2bbbef83499f590" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "thiserror" +version = "1.0.64" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d50af8abc119fb8bb6dbabcfa89656f46f84aa0ac7688088608076ad2b459a84" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.64" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "08904e7672f5eb876eaaf87e0ce17857500934f4981c4a0ab2b4aa98baac7fc3" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.79", +] + +[[package]] +name = "typenum" +version = "1.17.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "42ff0bf0c66b8238c6f3b578df37d0b7848e55df8577b3f74f92a69acceeb825" + +[[package]] +name = "unicode-ident" +version = "1.0.13" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e91b56cd4cadaeb79bbf1a5645f6b4f8dc5bde8834ad5894a8db35fda9efa1fe" + +[[package]] +name = "vcell" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" + +[[package]] +name = "version_check" +version = "0.9.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0b928f33d975fc6ad9f86c8f283853ad26bdd5b10b7f1542aa2fa15e2289105a" + +[[package]] +name = "void" +version = "1.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" + +[[package]] +name = "volatile-register" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de437e2a6208b014ab52972a27e59b33fa2920d3e00fe05026167a1c509d19cc" +dependencies = [ + "vcell", +] diff --git a/boards/stm32h743zi/Cargo.toml b/boards/stm32h743zi/Cargo.toml new file mode 100644 index 0000000..1f5b01d --- /dev/null +++ b/boards/stm32h743zi/Cargo.toml @@ -0,0 +1,32 @@ +[package] +name = "hyped_boards_stm32h743zi" +version = "0.1.0" +edition = "2021" + +[dependencies] +embassy-stm32 = { version = "0.1.0", features = ["defmt", "stm32h743zi", "memory-x", "unstable-pac", "time-driver-any", "exti"] , git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-sync = { version = "0.6.0", features = ["defmt"], git = "https://github.com/embassy-rs/embassy"} +embassy-executor = { version = "0.6.0", features = ["task-arena-size-32768", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-time = { version = "0.3.1", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-net = { version = "0.4.0", features = ["defmt", "tcp", "dhcpv4", "medium-ethernet"], git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} +embassy-futures = { version = "0.1.0", git = "https://github.com/embassy-rs/embassy", rev = "1c466b81e6af6b34b1f706318cc0870a459550b7"} + +defmt = "0.3" +defmt-rtt = "0.4" + +cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] } +cortex-m-rt = "0.7.0" +embedded-hal = "0.2.6" +panic-probe = { version = "0.3", features = ["print-defmt"] } +rand_core = "0.6.3" +critical-section = "1.1" +embedded-storage = "0.3.1" +static_cell = "2" + +heapless = { version = "0.8", default-features = false, features = ["serde"]} +rust-mqtt = { version = "0.3.0", default-features = false, features = ["defmt"] } +serde = { version = "1.0", default-features = false, features = ["derive"] } +serde-json-core = "0.1.0" +typenum = "1.17.0" + +hyped_core = { path = "../../lib/core" } diff --git a/boards/stm32h743zi/build.rs b/boards/stm32h743zi/build.rs new file mode 100644 index 0000000..8cd32d7 --- /dev/null +++ b/boards/stm32h743zi/build.rs @@ -0,0 +1,5 @@ +fn main() { + println!("cargo:rustc-link-arg-bins=--nmagic"); + println!("cargo:rustc-link-arg-bins=-Tlink.x"); + println!("cargo:rustc-link-arg-bins=-Tdefmt.x"); +} diff --git a/boards/stm32h743zi/src/bin/telemetry.rs b/boards/stm32h743zi/src/bin/telemetry.rs new file mode 100644 index 0000000..29224f0 --- /dev/null +++ b/boards/stm32h743zi/src/bin/telemetry.rs @@ -0,0 +1,125 @@ +#![no_std] +#![no_main] + +use defmt::*; +use embassy_executor::Spawner; +use embassy_net::{Stack, StackResources}; +use embassy_stm32::{ + bind_interrupts, + eth::{self, generic_smi::GenericSMI, Ethernet, PacketQueue}, + peripherals::{self, ETH}, + rcc, + rng::{self, Rng}, + time::Hertz, + Config, +}; +use embassy_time::{Duration, Timer}; +use hyped_boards_stm32h743zi::{ + config::{BOARD_STATIC_ADDRESS, GATEWAY_IP}, + log::log, + tasks::{ + heartbeat::heartbeat, + mqtt::{mqtt_recv_task, mqtt_send_task}, + }, +}; +use hyped_core::log_types::LogLevel; +use rand_core::RngCore; +use static_cell::StaticCell; +use {defmt_rtt as _, panic_probe as _}; + +bind_interrupts!(struct Irqs { + ETH => eth::InterruptHandler; + RNG => rng::InterruptHandler; +}); + +/// Task for running the network stack +#[embassy_executor::task] +pub async fn net_task(stack: &'static Stack>) -> ! { + stack.run().await +} + +#[embassy_executor::main] +async fn main(spawner: Spawner) -> ! { + let mut config = Config::default(); + { + use embassy_stm32::rcc::*; + config.rcc.hse = Some(Hse { + freq: Hertz(8_000_000), + mode: HseMode::Bypass, + }); + config.rcc.pll1 = Some(rcc::Pll { + source: PllSource::HSE, + prediv: PllPreDiv::DIV4, + mul: PllMul::MUL216, + divp: Some(rcc::PllDiv::DIV2), + divq: None, + divr: None, + }); + config.rcc.ahb_pre = AHBPrescaler::DIV2; // 200Mhz + config.rcc.apb1_pre = APBPrescaler::DIV2; // APB are additional clocks for external devices + config.rcc.apb2_pre = APBPrescaler::DIV2; // and just need to be set to some value less + config.rcc.apb3_pre = APBPrescaler::DIV2; // than the real clock + config.rcc.apb4_pre = APBPrescaler::DIV2; // + config.rcc.sys = Sysclk::PLL1_P; // 400Mhz + } + + let p = embassy_stm32::init(config); + + let mut rng = Rng::new(p.RNG, Irqs); + let mut seed = [0; 8]; + rng.fill_bytes(&mut seed); + let seed = u64::from_le_bytes(seed); + + let mac_addr: [u8; 6] = [0x00, 0x00, 0xDE, 0xAD, 0xBE, 0xEF]; + + static PACKETS: StaticCell> = StaticCell::new(); + let device = Ethernet::new( + PACKETS.init(PacketQueue::<4, 4>::new()), + p.ETH, + Irqs, + p.PA1, + p.PA2, + p.PC1, + p.PA7, + p.PC4, + p.PC5, + p.PG13, + p.PB13, + p.PG11, + GenericSMI::new(0), + mac_addr, + ); + + let config = embassy_net::Config::ipv4_static(embassy_net::StaticConfigV4 { + address: BOARD_STATIC_ADDRESS, + dns_servers: heapless::Vec::new(), + gateway: Some(GATEWAY_IP), + }); + + // Init network stack + static STACK: StaticCell>> = StaticCell::new(); + static RESOURCES: StaticCell> = StaticCell::new(); + let stack = &*STACK.init(Stack::new( + device, + config, + RESOURCES.init(StackResources::<3>::new()), + seed, + )); + + // Launch network task + unwrap!(spawner.spawn(net_task(stack))); + + // Ensure DHCP configuration is up before trying connect + stack.wait_config_up().await; + + log(LogLevel::Info, "Network stack initialized").await; + + // Launch MQTT send and receive tasks + unwrap!(spawner.spawn(mqtt_send_task(stack))); + unwrap!(spawner.spawn(mqtt_recv_task(stack))); + unwrap!(spawner.spawn(heartbeat())); + + loop { + Timer::after(Duration::from_secs(1)).await; + } +} diff --git a/boards/stm32h743zi/src/config.rs b/boards/stm32h743zi/src/config.rs new file mode 100644 index 0000000..8c1a0af --- /dev/null +++ b/boards/stm32h743zi/src/config.rs @@ -0,0 +1,9 @@ +use embassy_net::{Ipv4Address, Ipv4Cidr}; + +pub const BOARD_STATIC_IP: Ipv4Address = Ipv4Address::new(192, 168, 0, 55); +pub const BOARD_STATIC_ADDRESS: Ipv4Cidr = Ipv4Cidr::new(BOARD_STATIC_IP, 24); + +pub const MQTT_BROKER_IP: Ipv4Address = Ipv4Address::new(192, 168, 0, 65); +pub const MQTT_BROKER_ADDRESS: (Ipv4Address, u16) = (MQTT_BROKER_IP, 1883); + +pub const GATEWAY_IP: Ipv4Address = Ipv4Address::new(192, 168, 0, 1); diff --git a/boards/stm32h743zi/src/lib.rs b/boards/stm32h743zi/src/lib.rs new file mode 100644 index 0000000..79a340a --- /dev/null +++ b/boards/stm32h743zi/src/lib.rs @@ -0,0 +1,5 @@ +#![no_std] + +pub mod config; +pub mod log; +pub mod tasks; diff --git a/boards/stm32h743zi/src/log.rs b/boards/stm32h743zi/src/log.rs new file mode 100644 index 0000000..8e65d6f --- /dev/null +++ b/boards/stm32h743zi/src/log.rs @@ -0,0 +1,21 @@ +use crate::tasks::mqtt::SEND_CHANNEL; +use core::str::FromStr; +use defmt::{debug, error, info, warn}; +use heapless::String; +use hyped_core::{log_types::LogLevel, mqtt::MqttMessage, mqtt_topics::MqttTopics}; + +/// Log a message to the console and send it to the MQTT broker +pub async fn log(level: LogLevel, message: &str) { + match level { + LogLevel::Info => info!("{}", message), + LogLevel::Warn => warn!("{}", message), + LogLevel::Error => error!("{}", message), + LogLevel::Debug => debug!("{}", message), + } + SEND_CHANNEL + .send(MqttMessage { + topic: MqttTopics::to_string(&MqttTopics::Logs), + payload: String::<512>::from_str(message).unwrap(), + }) + .await; +} diff --git a/boards/stm32h743zi/src/tasks.rs b/boards/stm32h743zi/src/tasks.rs new file mode 100644 index 0000000..d445153 --- /dev/null +++ b/boards/stm32h743zi/src/tasks.rs @@ -0,0 +1,3 @@ +pub mod button; +pub mod heartbeat; +pub mod mqtt; diff --git a/boards/stm32h743zi/src/tasks/button.rs b/boards/stm32h743zi/src/tasks/button.rs new file mode 100644 index 0000000..01f18f6 --- /dev/null +++ b/boards/stm32h743zi/src/tasks/button.rs @@ -0,0 +1,38 @@ +use super::mqtt::SEND_CHANNEL; +use core::str::FromStr; +use embassy_stm32::gpio::{AnyPin, Input, Pull}; +use embassy_time::{Duration, Timer}; +use heapless::String; +use hyped_core::{mqtt::MqttMessage, mqtt_topics::MqttTopics}; +use serde::{Deserialize, Serialize}; +use typenum::consts::*; +use {defmt_rtt as _, panic_probe as _}; + +/// Struct to hold the state of the button +#[derive(Debug, Serialize, Deserialize)] +pub struct ButtonMqttMessage { + pub status: bool, +} + +/// Sends the state of the button over MQTT +/// (For testing purposes) +#[embassy_executor::task] +pub async fn button_task(pin: AnyPin) { + let button = Input::new(pin, Pull::Down); + loop { + SEND_CHANNEL + .send(MqttMessage { + topic: MqttTopics::to_string(&MqttTopics::Debug), + payload: String::<512>::from_str( + serde_json_core::to_string::(&ButtonMqttMessage { + status: button.is_high(), + }) + .unwrap() + .as_str(), + ) + .unwrap(), + }) + .await; + Timer::after(Duration::from_millis(100)).await; + } +} diff --git a/boards/stm32h743zi/src/tasks/heartbeat.rs b/boards/stm32h743zi/src/tasks/heartbeat.rs new file mode 100644 index 0000000..66410c2 --- /dev/null +++ b/boards/stm32h743zi/src/tasks/heartbeat.rs @@ -0,0 +1,22 @@ +use super::mqtt::SEND_CHANNEL; +use core::str::FromStr; +use defmt::debug; +use embassy_time::{Duration, Timer}; +use heapless::String; +use hyped_core::{mqtt::MqttMessage, mqtt_topics::MqttTopics}; +use {defmt_rtt as _, panic_probe as _}; + +/// Sends a heartbeat message to the MQTT broker every second +#[embassy_executor::task] +pub async fn heartbeat() { + loop { + SEND_CHANNEL + .send(MqttMessage { + topic: MqttTopics::to_string(&MqttTopics::Heartbeat), + payload: String::<512>::from_str("").unwrap(), + }) + .await; + debug!("Heartbeat sent"); + Timer::after(Duration::from_secs(1)).await; + } +} diff --git a/boards/stm32h743zi/src/tasks/mqtt.rs b/boards/stm32h743zi/src/tasks/mqtt.rs new file mode 100644 index 0000000..2c87a44 --- /dev/null +++ b/boards/stm32h743zi/src/tasks/mqtt.rs @@ -0,0 +1,150 @@ +use crate::{config::MQTT_BROKER_ADDRESS, log::log}; +use embassy_net::{tcp::TcpSocket, Stack}; +use embassy_stm32::{ + eth::{generic_smi::GenericSMI, Ethernet}, + peripherals::ETH, +}; +use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, channel::Channel}; +use embassy_time::{Duration, Timer}; +use hyped_core::{ + format, + format_string::show, + log_types::LogLevel, + mqtt::{HypedMqttClient, MqttMessage}, + mqtt_topics::MqttTopics, +}; +use {defmt_rtt as _, panic_probe as _}; + +/// Channel for sending messages to the MQTT broker +pub static SEND_CHANNEL: Channel = Channel::new(); + +/// Task for receiving messages from the MQTT broker +#[embassy_executor::task] +pub async fn mqtt_recv_task(stack: &'static Stack>) { + let mut rx_buffer: [u8; 4096] = [0; 4096]; + let mut tx_buffer: [u8; 4096] = [0; 4096]; + let mut socket = TcpSocket::new(stack, &mut rx_buffer, &mut tx_buffer); + + log(LogLevel::Info, "Connecting to Receive Socket...").await; + + match socket.connect(MQTT_BROKER_ADDRESS).await { + Ok(()) => { + log(LogLevel::Info, "Connected to Receive!").await; + } + Err(connection_error) => { + log( + LogLevel::Error, + format!(&mut [0u8; 1024], "Error connecting: {:?}", connection_error).unwrap(), + ) + .await; + } + }; + + const RECV_BUFFER_LEN: usize = 1024; + const WRITE_BUFFER_LEN: usize = 1024; + let mut recv_buffer = [0; RECV_BUFFER_LEN]; + let mut write_buffer = [0; WRITE_BUFFER_LEN]; + + let mut mqtt_client = HypedMqttClient::new( + socket, + &mut write_buffer, + RECV_BUFFER_LEN, + &mut recv_buffer, + WRITE_BUFFER_LEN, + "telemetry_board_receiver", + ); + + mqtt_client.connect_to_broker().await; + mqtt_client.subscribe("hyped/pod_2025/#").await; + + loop { + match mqtt_client.receive_message().await { + Ok((topic, message)) => match MqttTopics::from_string(topic) { + // Ignore heartbeat and log messages + Some(MqttTopics::Heartbeat) => {} + Some(MqttTopics::Logs) => {} + Some(_) => { + log( + LogLevel::Info, + format!( + &mut [0u8; 1024], + "Received message on topic {}: {}", topic, message + ) + .unwrap(), + ) + .await + } + None => { + log( + LogLevel::Warn, + format!( + &mut [0u8; 1024], + "Received message on unknown topic {}: {}", topic, message + ) + .unwrap(), + ) + .await + } + }, + Err(err) => { + if err == rust_mqtt::packet::v5::reason_codes::ReasonCode::NetworkError { + break; + } + log( + LogLevel::Error, + format!(&mut [0u8; 1024], "Error receiving message: {:?}", err).unwrap(), + ) + .await + } + } + Timer::after(Duration::from_millis(100)).await; + } +} + +/// Task for sending messages from `SEND_CHANNEL` to the MQTT broker +#[embassy_executor::task] +pub async fn mqtt_send_task(stack: &'static Stack>) { + let mut rx_buffer: [u8; 4096] = [0; 4096]; + let mut tx_buffer: [u8; 4096] = [0; 4096]; + let mut socket = TcpSocket::new(stack, &mut rx_buffer, &mut tx_buffer); + socket.set_timeout(Some(embassy_time::Duration::from_secs(60))); + + log(LogLevel::Info, "Connecting to Send Socket...").await; + + match socket.connect(MQTT_BROKER_ADDRESS).await { + Ok(()) => log(LogLevel::Info, "Connected to Send!").await, + Err(connection_error) => { + log( + LogLevel::Error, + format!(&mut [0u8; 1024], "Error connecting: {:?}", connection_error).unwrap(), + ) + .await; + } + }; + + const RECV_BUFFER_LEN: usize = 1024; + const WRITE_BUFFER_LEN: usize = 1024; + let mut recv_buffer = [0; RECV_BUFFER_LEN]; + let mut write_buffer = [0; WRITE_BUFFER_LEN]; + + let mut mqtt_client = HypedMqttClient::new( + socket, + &mut write_buffer, + RECV_BUFFER_LEN, + &mut recv_buffer, + WRITE_BUFFER_LEN, + "telemetry_board_sender", + ); + + mqtt_client.connect_to_broker().await; + + loop { + while !SEND_CHANNEL.is_empty() { + let message = SEND_CHANNEL.receive().await; + mqtt_client + .send_message(message.topic.as_str(), message.payload.as_bytes(), false) + .await; + } + Timer::after(Duration::from_millis(100)).await; + } +} diff --git a/lib/core/Cargo.lock b/lib/core/Cargo.lock new file mode 100644 index 0000000..ca54f96 --- /dev/null +++ b/lib/core/Cargo.lock @@ -0,0 +1,234 @@ +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "bitflags" +version = "1.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" + +[[package]] +name = "byteorder" +version = "1.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1fd0f2584146f6f2ef48085050886acf353beff7305ebd1ae69500e27c67f64b" + +[[package]] +name = "defmt" +version = "0.3.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a99dd22262668b887121d4672af5a64b238f026099f1a2a1b322066c9ecfe9e0" +dependencies = [ + "bitflags", + "defmt-macros", +] + +[[package]] +name = "defmt-macros" +version = "0.3.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e3a9f309eff1f79b3ebdf252954d90ae440599c26c2c553fe87a2d17195f2dcb" +dependencies = [ + "defmt-parser", + "proc-macro-error", + "proc-macro2", + "quote", + "syn 2.0.72", +] + +[[package]] +name = "defmt-parser" +version = "0.3.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ff4a5fefe330e8d7f31b16a318f9ce81000d8e35e69b93eae154d16d2278f70f" +dependencies = [ + "thiserror", +] + +[[package]] +name = "embedded-io" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "edd0f118536f44f5ccd48bcb8b111bdc3de888b58c74639dfb034a357d0f206d" + +[[package]] +name = "embedded-io-async" +version = "0.6.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3ff09972d4073aa8c299395be75161d582e7629cd663171d62af73c8d50dba3f" +dependencies = [ + "embedded-io", +] + +[[package]] +name = "hash32" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "47d60b12902ba28e2730cd37e95b8c9223af2808df9e902d4df49588d1470606" +dependencies = [ + "byteorder", +] + +[[package]] +name = "heapless" +version = "0.8.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0bfb9eb618601c89945a70e254898da93b13be0388091d42117462b265bb3fad" +dependencies = [ + "hash32", + "serde", + "stable_deref_trait", +] + +[[package]] +name = "hyped_core" +version = "0.1.0" +dependencies = [ + "defmt", + "embedded-io-async", + "heapless", + "rand_core", + "rust-mqtt", + "serde", +] + +[[package]] +name = "proc-macro-error" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" +dependencies = [ + "proc-macro-error-attr", + "proc-macro2", + "quote", + "syn 1.0.109", + "version_check", +] + +[[package]] +name = "proc-macro-error-attr" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" +dependencies = [ + "proc-macro2", + "quote", + "version_check", +] + +[[package]] +name = "proc-macro2" +version = "1.0.86" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5e719e8df665df0d1c8fbfd238015744736151d4445ec0836b8e628aae103b77" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "quote" +version = "1.0.36" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0fa76aaf39101c457836aec0ce2316dbdc3ab723cdda1c6bd4e6ad4208acaca7" +dependencies = [ + "proc-macro2", +] + +[[package]] +name = "rand_core" +version = "0.6.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" + +[[package]] +name = "rust-mqtt" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8f71160765f368fd9a84e0955e2ddb6d64ac9018fee1c5323354d6d08c816b40" +dependencies = [ + "defmt", + "embedded-io", + "embedded-io-async", + "heapless", + "rand_core", +] + +[[package]] +name = "serde" +version = "1.0.204" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bc76f558e0cbb2a839d37354c575f1dc3fdc6546b5be373ba43d95f231bf7c12" +dependencies = [ + "serde_derive", +] + +[[package]] +name = "serde_derive" +version = "1.0.204" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e0cd7e117be63d3c3678776753929474f3b04a43a080c744d6b0ae2a8c28e222" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.72", +] + +[[package]] +name = "stable_deref_trait" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" + +[[package]] +name = "syn" +version = "1.0.109" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" +dependencies = [ + "proc-macro2", + "unicode-ident", +] + +[[package]] +name = "syn" +version = "2.0.72" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dc4b9b9bf2add8093d3f2c0204471e951b2285580335de42f9d2534f3ae7a8af" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "thiserror" +version = "1.0.63" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c0342370b38b6a11b6cc11d6a805569958d54cfa061a29969c3b5ce2ea405724" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.63" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a4558b58466b9ad7ca0f102865eccc95938dca1a74a856f2b57b6629050da261" +dependencies = [ + "proc-macro2", + "quote", + "syn 2.0.72", +] + +[[package]] +name = "unicode-ident" +version = "1.0.12" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3354b9ac3fae1ff6755cb6db53683adb661634f67557942dea4facebec0fee4b" + +[[package]] +name = "version_check" +version = "0.9.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "49874b5167b65d7193b8aba1567f5c7d93d001cafc34600cee003eda787e483f" diff --git a/lib/core/src/mqtt.rs b/lib/core/src/mqtt.rs index 59e69ae..0ddb6e7 100644 --- a/lib/core/src/mqtt.rs +++ b/lib/core/src/mqtt.rs @@ -2,8 +2,11 @@ use defmt::{info, warn}; use embassy_net::tcp::TcpSocket; use heapless::String; use rust_mqtt::{ - client::{client::MqttClient, client_config::ClientConfig}, - packet::v5::reason_codes::ReasonCode, + client::{ + client::MqttClient, + client_config::{ClientConfig, MqttVersion}, + }, + packet::v5::{publish_packet::QualityOfService, reason_codes::ReasonCode}, utils::rng_generator::CountingRng, }; @@ -46,16 +49,14 @@ impl<'a> HypedMqttClient<'a, TcpSocket<'a>, CountingRng> { /// Initialise the MQTT client configuration with the given client ID pub fn initialise_mqtt_config(client_id: &str) -> ClientConfig<'_, 5, CountingRng> { - let mut config = ClientConfig::new( - rust_mqtt::client::client_config::MqttVersion::MQTTv5, - CountingRng(20000), - ); - config.add_max_subscribe_qos(rust_mqtt::packet::v5::publish_packet::QualityOfService::QoS1); + let mut config = ClientConfig::new(MqttVersion::MQTTv5, CountingRng(20000)); + config.add_max_subscribe_qos(QualityOfService::QoS1); config.add_client_id(client_id); config.max_packet_size = 100; config } +// Implement send_message for HypedMqttClient impl<'a, T: embedded_io_async::Read + embedded_io_async::Write, R: rand_core::RngCore> HypedMqttClient<'a, T, R> { @@ -76,12 +77,7 @@ impl<'a, T: embedded_io_async::Read + embedded_io_async::Write, R: rand_core::Rn pub async fn send_message(&mut self, topic: &str, message: &[u8], retain: bool) { match self .client - .send_message( - topic, - message, - rust_mqtt::packet::v5::publish_packet::QualityOfService::QoS1, - retain, - ) + .send_message(topic, message, QualityOfService::QoS1, retain) .await { Ok(()) => {} diff --git a/lib/core/src/mqtt_topics.rs b/lib/core/src/mqtt_topics.rs index 207a9e1..5bf4dd5 100644 --- a/lib/core/src/mqtt_topics.rs +++ b/lib/core/src/mqtt_topics.rs @@ -11,51 +11,60 @@ pub enum MqttTopics { Displacement, Velocity, Acceleration, + Heartbeat, Logs, + Debug, + Test, } impl MqttTopics { /// Convert an `MqttTopics` enum variant to a string pub fn to_string(&self) -> String<48> { match self { - MqttTopics::State => String::<48>::from_str("hyped/cart_2024/state/state").unwrap(), + MqttTopics::State => String::<48>::from_str("hyped/pod_2025/state/state").unwrap(), MqttTopics::StateRequest => { - String::<48>::from_str("hyped/cart_2024/state/state_request").unwrap() + String::<48>::from_str("hyped/pod_2025/state/state_request").unwrap() } MqttTopics::Accelerometer => { - String::<48>::from_str("hyped/cart_2024/measurement/accelerometer").unwrap() + String::<48>::from_str("hyped/pod_2025/measurement/accelerometer").unwrap() } MqttTopics::OpticalFlow => { - String::<48>::from_str("hyped/cart_2024/measurement/optical_flow").unwrap() + String::<48>::from_str("hyped/pod_2025/measurement/optical_flow").unwrap() } MqttTopics::Keyence => { - String::<48>::from_str("hyped/cart_2024/measurement/keyence").unwrap() + String::<48>::from_str("hyped/pod_2025/measurement/keyence").unwrap() } MqttTopics::Displacement => { - String::<48>::from_str("hyped/cart_2024/navigation/displacement").unwrap() + String::<48>::from_str("hyped/pod_2025/navigation/displacement").unwrap() } MqttTopics::Velocity => { - String::<48>::from_str("hyped/cart_2024/navigation/velocity").unwrap() + String::<48>::from_str("hyped/pod_2025/navigation/velocity").unwrap() } MqttTopics::Acceleration => { - String::<48>::from_str("hyped/cart_2024/navigation/acceleration").unwrap() + String::<48>::from_str("hyped/pod_2025/navigation/acceleration").unwrap() } - MqttTopics::Logs => String::<48>::from_str("hyped/cart_2024/logs").unwrap(), + MqttTopics::Heartbeat => String::<48>::from_str("hyped/pod_2025/heartbeat").unwrap(), + MqttTopics::Logs => String::<48>::from_str("hyped/pod_2025/logs").unwrap(), + MqttTopics::Debug => String::<48>::from_str("debug").unwrap(), + MqttTopics::Test => String::<48>::from_str("test").unwrap(), } } /// Get an `MqttTopics` enum variant from a string pub fn from_string(topic: &str) -> Option { match topic { - "hyped/cart_2024/state/state" => Some(MqttTopics::State), - "hyped/cart_2024/state/state_request" => Some(MqttTopics::StateRequest), - "hyped/cart_2024/measurement/accelerometer" => Some(MqttTopics::Accelerometer), - "hyped/cart_2024/measurement/optical_flow" => Some(MqttTopics::OpticalFlow), - "hyped/cart_2024/measurement/keyence" => Some(MqttTopics::Keyence), - "hyped/cart_2024/navigation/displacement" => Some(MqttTopics::Displacement), - "hyped/cart_2024/navigation/velocity" => Some(MqttTopics::Velocity), - "hyped/cart_2024/navigation/acceleration" => Some(MqttTopics::Acceleration), - "hyped/cart_2024/logs" => Some(MqttTopics::Logs), + "hyped/pod_2025/state/state" => Some(MqttTopics::State), + "hyped/pod_2025/state/state_request" => Some(MqttTopics::StateRequest), + "hyped/pod_2025/measurement/accelerometer" => Some(MqttTopics::Accelerometer), + "hyped/pod_2025/measurement/optical_flow" => Some(MqttTopics::OpticalFlow), + "hyped/pod_2025/measurement/keyence" => Some(MqttTopics::Keyence), + "hyped/pod_2025/navigation/displacement" => Some(MqttTopics::Displacement), + "hyped/pod_2025/navigation/velocity" => Some(MqttTopics::Velocity), + "hyped/pod_2025/navigation/acceleration" => Some(MqttTopics::Acceleration), + "hyped/pod_2025/heartbeat" => Some(MqttTopics::Heartbeat), + "hyped/pod_2025/logs" => Some(MqttTopics::Logs), + "debug" => Some(MqttTopics::Debug), + "test" => Some(MqttTopics::Test), _ => None, } } From 14148406721275fbabca4e25c5991ccd7ac8cacb Mon Sep 17 00:00:00 2001 From: David Beechey Date: Tue, 5 Nov 2024 10:15:37 +0000 Subject: [PATCH 7/8] INFRA - Add STM32H743ZI board to CI, add caching (#44) --- .github/workflows/ci.yml | 20 +++++++++++++++++--- .github/workflows/lint.yml | 16 ++++++++++++++-- boards/stm32h743zi/src/tasks/heartbeat.rs | 2 +- 3 files changed, 32 insertions(+), 6 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 1be9d12..96eef82 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -20,10 +20,24 @@ jobs: steps: - uses: actions/checkout@v4 - run: rustup update ${{ matrix.toolchain }} && rustup default ${{ matrix.toolchain }} + - uses: Swatinem/rust-cache@v2 - run: cargo build --verbose - run: cargo test --verbose + + build_boards: + name: Cargo Build (boards) + runs-on: ubuntu-latest + strategy: + matrix: + board: + - stm32l476rg + - stm32h743zi + - stm32f767zi + steps: + - uses: actions/checkout@v4 - run: rustup target add thumbv7em-none-eabihf + - uses: Swatinem/rust-cache@v2 + with: + key: ${{ matrix.board }} - run: cargo build --verbose - working-directory: boards/stm32l476rg - - run: cargo build --verbose - working-directory: boards/stm32f767zi + working-directory: boards/${{ matrix.board }} diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index cac08ed..a170d39 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -16,8 +16,20 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v4 - - name: Run rustfmt - run: cargo fmt --all -- --check + - run: cargo fmt --all -- --check + + rust-fmt-boards: + name: Run rustfmt (boards) + runs-on: ubuntu-latest + strategy: + matrix: + board: + - stm32l476rg + - stm32h743zi + - stm32f767zi + steps: + - uses: actions/checkout@v4 + - run: cargo fmt --manifest-path boards/${{ matrix.board }}/Cargo.toml -- --check typos: name: Spell check with typos diff --git a/boards/stm32h743zi/src/tasks/heartbeat.rs b/boards/stm32h743zi/src/tasks/heartbeat.rs index 66410c2..152136e 100644 --- a/boards/stm32h743zi/src/tasks/heartbeat.rs +++ b/boards/stm32h743zi/src/tasks/heartbeat.rs @@ -10,13 +10,13 @@ use {defmt_rtt as _, panic_probe as _}; #[embassy_executor::task] pub async fn heartbeat() { loop { + debug!("Sending heartbeat..."); SEND_CHANNEL .send(MqttMessage { topic: MqttTopics::to_string(&MqttTopics::Heartbeat), payload: String::<512>::from_str("").unwrap(), }) .await; - debug!("Heartbeat sent"); Timer::after(Duration::from_secs(1)).await; } } From 36b19994313f8f8f0d48b478e81a8a0173f0316e Mon Sep 17 00:00:00 2001 From: lylebuist <102750153+lylebuist@users.noreply.github.com> Date: Fri, 8 Nov 2024 10:24:42 +0000 Subject: [PATCH 8/8] LOC - Preprocess Keyence (#30) Co-authored-by: David Beechey --- Cargo.lock | 109 ++++-------------- lib/localisation/Cargo.toml | 3 +- lib/localisation/src/lib.rs | 2 + lib/localisation/src/preprocessing.rs | 1 + lib/localisation/src/preprocessing/keyence.rs | 96 +++++++++++++++ 5 files changed, 123 insertions(+), 88 deletions(-) create mode 100644 lib/localisation/src/preprocessing.rs diff --git a/Cargo.lock b/Cargo.lock index 6db5714..d78c302 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -4,9 +4,9 @@ version = 3 [[package]] name = "anyhow" -version = "1.0.91" +version = "1.0.93" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c042108f3ed77fd83760a5fd79b53be043192bb3b9dba91d8c574c0ada7850c8" +checksum = "4c95c10ba0b00a02636238b814946408b1322d5ac4760326e6fb8ec956d85775" [[package]] name = "approx" @@ -29,12 +29,6 @@ version = "1.3.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" -[[package]] -name = "bytemuck" -version = "1.19.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8334215b81e418a0a7bdb8ef0849474f40bb10c8b71f1c4ed315cff49f32494d" - [[package]] name = "byteorder" version = "1.5.0" @@ -73,7 +67,7 @@ dependencies = [ "proc-macro-error", "proc-macro2", "quote", - "syn 2.0.82", + "syn 2.0.87", ] [[package]] @@ -263,9 +257,9 @@ dependencies = [ [[package]] name = "hashbrown" -version = "0.15.0" +version = "0.15.1" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1e087f84d4f86bf4b218b927129862374b72199ae7d8657835f1e89000eea4fb" +checksum = "3a9bfc1af68b1726ea47d3d5109de126281def866b33970e10fbab11b5dafab3" [[package]] name = "heapless" @@ -315,6 +309,7 @@ version = "0.1.0" name = "hyped_localisation" version = "0.1.0" dependencies = [ + "heapless", "nalgebra", ] @@ -365,16 +360,6 @@ version = "0.8.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "0ca88d725a0a943b096803bd34e73a4437208b6077654cc4ecb2947a5f91618d" -[[package]] -name = "matrixmultiply" -version = "0.3.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9380b911e3e96d10c1f415da0876389aaf1b56759054eeb0de7df940c456ba1a" -dependencies = [ - "autocfg", - "rawpointer", -] - [[package]] name = "memchr" version = "2.7.4" @@ -383,13 +368,11 @@ checksum = "78ca9ab1a0babb1e7d5695e3530886289c18cf2f87ec19a575a0abdce112e3a3" [[package]] name = "nalgebra" -version = "0.33.1" +version = "0.33.2" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3bf139e93ad757869338ad85239cb1d6c067b23b94e5846e637ca6328ee4be60" +checksum = "26aecdf64b707efd1310e3544d709c5c0ac61c13756046aaaba41be5c4f66a3b" dependencies = [ "approx", - "matrixmultiply", - "nalgebra-macros", "num-complex", "num-rational", "num-traits", @@ -397,17 +380,6 @@ dependencies = [ "typenum", ] -[[package]] -name = "nalgebra-macros" -version = "0.2.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "254a5372af8fc138e36684761d3c0cdb758a4410e938babcff1c860ce14ddbfc" -dependencies = [ - "proc-macro2", - "quote", - "syn 2.0.82", -] - [[package]] name = "nb" version = "0.1.3" @@ -429,16 +401,6 @@ version = "0.6.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "43794a0ace135be66a25d3ae77d41b91615fb68ae937f904090203e81f755b65" -[[package]] -name = "num-bigint" -version = "0.4.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a5e44f723f1133c9deac646763579fdb3ac745e418f2a7af9cd0c431da1f20b9" -dependencies = [ - "num-integer", - "num-traits", -] - [[package]] name = "num-complex" version = "0.4.6" @@ -463,7 +425,6 @@ version = "0.4.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "f83d14da390562dca69fc84082e73e548e1ad308d24accdedd2720017cb37824" dependencies = [ - "num-bigint", "num-integer", "num-traits", ] @@ -485,9 +446,9 @@ checksum = "57c0d7b74b563b49d38dae00a0c37d4d6de9b432382b2892f0574ddcae73fd0a" [[package]] name = "pin-project-lite" -version = "0.2.14" +version = "0.2.15" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bda66fc9667c18cb2758a2ac84d1167245054bcf85d5d1aaa6923f45801bdd02" +checksum = "915a1e146535de9163f3987b8944ed8cf49a18bb0056bcebcdcece385cece4ff" [[package]] name = "pin-utils" @@ -543,12 +504,6 @@ version = "0.6.4" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" -[[package]] -name = "rawpointer" -version = "0.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "60a357793950651c4ed0f3f52338f53b2f809f32d83a07f72909fa13e4c6c1e3" - [[package]] name = "rust-mqtt" version = "0.3.0" @@ -568,33 +523,24 @@ version = "1.0.18" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "f3cb5ba0dc43242ce17de99c180e96db90b235b8a9fdc9543c96d2209116bd9f" -[[package]] -name = "safe_arch" -version = "0.7.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c3460605018fdc9612bce72735cba0d27efbcd9904780d44c7e3a9948f96148a" -dependencies = [ - "bytemuck", -] - [[package]] name = "serde" -version = "1.0.213" +version = "1.0.214" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3ea7893ff5e2466df8d720bb615088341b295f849602c6956047f8f80f0e9bc1" +checksum = "f55c3193aca71c12ad7890f1785d2b73e1b9f63a0bbc353c08ef26fe03fc56b5" dependencies = [ "serde_derive", ] [[package]] name = "serde_derive" -version = "1.0.213" +version = "1.0.214" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7e85ad2009c50b58e87caa8cd6dac16bdf511bbfb7af6c33df902396aa480fa5" +checksum = "de523f781f095e28fa605cdce0f8307e451cc0fd14e2eb4cd2e98a355b147766" dependencies = [ "proc-macro2", "quote", - "syn 2.0.82", + "syn 2.0.87", ] [[package]] @@ -622,7 +568,6 @@ dependencies = [ "num-complex", "num-traits", "paste", - "wide", ] [[package]] @@ -657,9 +602,9 @@ dependencies = [ [[package]] name = "syn" -version = "2.0.82" +version = "2.0.87" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "83540f837a8afc019423a8edb95b52a8effe46957ee402287f4292fae35be021" +checksum = "25aa4ce346d03a6dcd68dd8b4010bcb74e54e62c90c573f394c46eae99aba32d" dependencies = [ "proc-macro2", "quote", @@ -668,22 +613,22 @@ dependencies = [ [[package]] name = "thiserror" -version = "1.0.65" +version = "1.0.68" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5d11abd9594d9b38965ef50805c5e469ca9cc6f197f883f717e0269a3057b3d5" +checksum = "02dd99dc800bbb97186339685293e1cc5d9df1f8fae2d0aecd9ff1c77efea892" dependencies = [ "thiserror-impl", ] [[package]] name = "thiserror-impl" -version = "1.0.65" +version = "1.0.68" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ae71770322cbd277e69d762a16c444af02aa0575ac0d174f0b9562d3b37f8602" +checksum = "a7c61ec9a6f64d2793d8a45faba21efbe3ced62a886d44c36a009b2b519b4c7e" dependencies = [ "proc-macro2", "quote", - "syn 2.0.82", + "syn 2.0.87", ] [[package]] @@ -709,13 +654,3 @@ name = "void" version = "1.0.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" - -[[package]] -name = "wide" -version = "0.7.28" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b828f995bf1e9622031f8009f8481a85406ce1f4d4588ff746d872043e855690" -dependencies = [ - "bytemuck", - "safe_arch", -] diff --git a/lib/localisation/Cargo.toml b/lib/localisation/Cargo.toml index d9f2753..e6fdb7a 100644 --- a/lib/localisation/Cargo.toml +++ b/lib/localisation/Cargo.toml @@ -4,4 +4,5 @@ version = "0.1.0" edition = "2021" [dependencies] -nalgebra = "0.33.0" +nalgebra = { version = "0.33.0", default-features = false } +heapless = "0.8.0" diff --git a/lib/localisation/src/lib.rs b/lib/localisation/src/lib.rs index 0c9ac1a..b012596 100644 --- a/lib/localisation/src/lib.rs +++ b/lib/localisation/src/lib.rs @@ -1 +1,3 @@ #![no_std] + +pub mod preprocessing; diff --git a/lib/localisation/src/preprocessing.rs b/lib/localisation/src/preprocessing.rs new file mode 100644 index 0000000..e1de1ed --- /dev/null +++ b/lib/localisation/src/preprocessing.rs @@ -0,0 +1 @@ +pub mod keyence; diff --git a/lib/localisation/src/preprocessing/keyence.rs b/lib/localisation/src/preprocessing/keyence.rs index 8b13789..fd81cbb 100644 --- a/lib/localisation/src/preprocessing/keyence.rs +++ b/lib/localisation/src/preprocessing/keyence.rs @@ -1 +1,97 @@ +use heapless::Vec; +#[derive(PartialEq, Debug)] +pub enum SensorChecks { + Acceptable, + Unnaceptable, +} + +/// Checks if the two Keyence sensors are in agreement. +/// If the sensors disagree for two consecutive readings, the check fails. +pub struct KeyenceAgrees { + previous_keyence_agreement: bool, +} + +impl Default for KeyenceAgrees { + fn default() -> Self { + Self::new() + } +} + +impl KeyenceAgrees { + pub fn new() -> Self { + KeyenceAgrees { + previous_keyence_agreement: true, + } + } + + pub fn check_keyence_agrees(&mut self, keyence_data: Vec) -> SensorChecks { + if keyence_data[0] != keyence_data[1] && !self.previous_keyence_agreement { + return SensorChecks::Unnaceptable; + } else { + self.previous_keyence_agreement = keyence_data[0] == keyence_data[1]; + } + + SensorChecks::Acceptable + } +} + +#[cfg(test)] +mod tests { + use super::*; + + #[test] + fn test_acceptable_success() { + let keyence_data: Vec = Vec::from_slice(&[true, true]).unwrap(); + let mut keyence_agrees = KeyenceAgrees::new(); + let desired_outcome = SensorChecks::Acceptable; + let result = keyence_agrees.check_keyence_agrees(keyence_data); + assert_eq!(result, desired_outcome); + } + + #[test] + fn test_acceptable_false_success() { + let keyence_data: Vec = Vec::from_slice(&[true, false]).unwrap(); + let mut keyence_agrees = KeyenceAgrees::new(); + let desired_outcome = SensorChecks::Acceptable; + let result = keyence_agrees.check_keyence_agrees(keyence_data); + assert_eq!(result, desired_outcome); + } + + #[test] + fn test_acceptable_second_false_success() { + let first_keyence_data: Vec = Vec::from_slice(&[true, true]).unwrap(); + let second_keyence_data: Vec = Vec::from_slice(&[true, false]).unwrap(); + let mut keyence_agrees = KeyenceAgrees::new(); + let desired_outcome = SensorChecks::Acceptable; + let initial_try = keyence_agrees.check_keyence_agrees(first_keyence_data); + let result = keyence_agrees.check_keyence_agrees(second_keyence_data); + assert_eq!(initial_try, desired_outcome); + assert_eq!(result, desired_outcome); + } + + #[test] + fn test_acceptable_prev_false_success() { + let first_keyence_data: Vec = Vec::from_slice(&[true, false]).unwrap(); + let second_keyence_data: Vec = Vec::from_slice(&[true, true]).unwrap(); + let mut keyence_agrees = KeyenceAgrees::new(); + let desired_outcome = SensorChecks::Acceptable; + let initial_try = keyence_agrees.check_keyence_agrees(first_keyence_data); + let result = keyence_agrees.check_keyence_agrees(second_keyence_data); + assert_eq!(initial_try, desired_outcome); + assert_eq!(result, desired_outcome); + } + + #[test] + fn test_unnacceptable_prev_false_success() { + let first_keyence_data: Vec = Vec::from_slice(&[true, false]).unwrap(); + let second_keyence_data: Vec = Vec::from_slice(&[true, false]).unwrap(); + let mut keyence_agrees = KeyenceAgrees::new(); + let first_outcome = SensorChecks::Acceptable; + let second_outcome = SensorChecks::Unnaceptable; + let initial_try = keyence_agrees.check_keyence_agrees(first_keyence_data); + let result = keyence_agrees.check_keyence_agrees(second_keyence_data); + assert_eq!(initial_try, first_outcome); + assert_eq!(result, second_outcome); + } +}