Compare commits
35 Commits
e20b474dfd
...
feature/mq
| Author | SHA1 | Date | |
|---|---|---|---|
| bd257b89f0 | |||
| 4debbfb39e | |||
| d83189417a | |||
| 3c92cf0c26 | |||
|
96023c8dc3
|
|||
|
7497a8c05d
|
|||
|
d3d8d829be
|
|||
|
6889ba4561
|
|||
|
18095349f3
|
|||
|
3d8fd893f5
|
|||
|
1bea7ef2f4
|
|||
|
f5b9674840
|
|||
|
6f22881007
|
|||
|
1d8af1b6c4
|
|||
|
2c532359fc
|
|||
|
53819484fb
|
|||
|
1151d099cf
|
|||
|
3feaacd460
|
|||
|
e15e78cc26
|
|||
|
d9aa96a3cb
|
|||
|
ecf989b859
|
|||
|
db401aac55
|
|||
| ecb7707357 | |||
|
4cf7a1c94f
|
|||
|
9155676e06
|
|||
|
e05f3d768f
|
|||
| cf58486cf5 | |||
| cfe23c8a09 | |||
| 3d18b0dbf6 | |||
| 7ebc147f51 | |||
| f0bda32d7a | |||
| 76f59b093d | |||
| 7fc8d0c882 | |||
| 6d5bb5b966 | |||
| 336961f0a0 |
10
bin/build-esp-plant-dev-tools.sh
Executable file
10
bin/build-esp-plant-dev-tools.sh
Executable file
@@ -0,0 +1,10 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
CONTAINER_NAME="localhost/esp-plant-dev-tools:latest"
|
||||
CONTAINER_TOOLS_BASEDIR="$(dirname "$(readlink -f "$0")")"
|
||||
|
||||
pushd "$CONTAINER_TOOLS_BASEDIR"
|
||||
podman build -t "$CONTAINER_NAME" -f "esp-plant-dev-tools.Containerfile" .
|
||||
popd
|
||||
16
bin/esp-plant-dev-tools.Containerfile
Normal file
16
bin/esp-plant-dev-tools.Containerfile
Normal file
@@ -0,0 +1,16 @@
|
||||
FROM debian:latest
|
||||
|
||||
RUN apt update -y && apt upgrade -y && apt install unzip curl xz-utils nodejs -y
|
||||
|
||||
RUN cd /root && \
|
||||
curl -L -o xpack-riscv-toolchain.tar.gz "https://github.com/xpack-dev-tools/riscv-none-elf-gcc-xpack/releases/download/v14.2.0-3/xpack-riscv-none-elf-gcc-14.2.0-3-linux-x64.tar.gz" && \
|
||||
mkdir xpack-toolchain && \
|
||||
tar -xvf xpack-riscv-toolchain.tar.gz -C xpack-toolchain --strip-components=1 && \
|
||||
mv xpack-toolchain/bin/* /usr/local/bin && \
|
||||
mv xpack-toolchain/lib/ /usr/local && \
|
||||
mv xpack-toolchain/lib64/ /usr/local && \
|
||||
mv xpack-toolchain/libexec /usr/local && \
|
||||
mv xpack-toolchain/riscv-none-elf /usr/local && \
|
||||
rm -rf xpack-toolchain xpack-riscv-toolchain.tar.gz
|
||||
|
||||
RUN apt install npm -y
|
||||
29
bin/npm
Executable file
29
bin/npm
Executable file
@@ -0,0 +1,29 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
CONTAINER_IMAGE="localhost/esp-plant-dev-tools:latest"
|
||||
CONTAINER_TOOLS_BASEDIR="$(dirname "$(readlink -f "$0")")"
|
||||
PLANTCTL_PROJECT_DIR="$(readlink -f "$CONTAINER_TOOLS_BASEDIR/..")"
|
||||
|
||||
function _fatal {
|
||||
echo -e "\e[31mERROR\e[0m $(</dev/stdin)$*" 1>&2
|
||||
exit 1
|
||||
}
|
||||
|
||||
declare -a PODMAN_ARGS=(
|
||||
"--rm" "-i" "--log-driver=none"
|
||||
"-v" "$PLANTCTL_PROJECT_DIR:$PLANTCTL_PROJECT_DIR:rw"
|
||||
"-v" "$PWD:$PWD:rw"
|
||||
"-w" "$PWD"
|
||||
)
|
||||
|
||||
[[ -t 1 ]] && PODMAN_ARGS+=("-t")
|
||||
|
||||
if ! podman image exists "$CONTAINER_IMAGE"; then
|
||||
#attempt to build container
|
||||
"$CONTAINER_TOOLS_BASEDIR/build-esp-plant-dev-tools.sh" 1>&2 ||
|
||||
_fatal "faild to build local image, cannot continue! … please ensure you have an internet connection"
|
||||
fi
|
||||
|
||||
podman run "${PODMAN_ARGS[@]}" --entrypoint npm "$CONTAINER_IMAGE" "$@"
|
||||
29
bin/npx
Executable file
29
bin/npx
Executable file
@@ -0,0 +1,29 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
CONTAINER_IMAGE="localhost/esp-plant-dev-tools:latest"
|
||||
CONTAINER_TOOLS_BASEDIR="$(dirname "$(readlink -f "$0")")"
|
||||
PLANTCTL_PROJECT_DIR="$(readlink -f "$CONTAINER_TOOLS_BASEDIR/..")"
|
||||
|
||||
function _fatal {
|
||||
echo -e "\e[31mERROR\e[0m $(</dev/stdin)$*" 1>&2
|
||||
exit 1
|
||||
}
|
||||
|
||||
declare -a PODMAN_ARGS=(
|
||||
"--rm" "-i" "--log-driver=none"
|
||||
"-v" "$PLANTCTL_PROJECT_DIR:$PLANTCTL_PROJECT_DIR:rw"
|
||||
"-v" "$PWD:$PWD:rw"
|
||||
"-w" "$PWD"
|
||||
)
|
||||
|
||||
[[ -t 1 ]] && PODMAN_ARGS+=("-t")
|
||||
|
||||
if ! podman image exists "$CONTAINER_IMAGE"; then
|
||||
#attempt to build container
|
||||
"$CONTAINER_TOOLS_BASEDIR/build-esp-plant-dev-tools.sh" 1>&2 ||
|
||||
_fatal "faild to build local image, cannot continue! … please ensure you have an internet connection"
|
||||
fi
|
||||
|
||||
podman run "${PODMAN_ARGS[@]}" --entrypoint npx "$CONTAINER_IMAGE" "$@"
|
||||
29
bin/riscv32-unknown-elf-gcc
Executable file
29
bin/riscv32-unknown-elf-gcc
Executable file
@@ -0,0 +1,29 @@
|
||||
#!/usr/bin/env bash
|
||||
|
||||
set -euo pipefail
|
||||
|
||||
CONTAINER_IMAGE="localhost/esp-plant-dev-tools:latest"
|
||||
CONTAINER_TOOLS_BASEDIR="$(dirname "$(readlink -f "$0")")"
|
||||
PLANTCTL_PROJECT_DIR="$(readlink -f "$CONTAINER_TOOLS_BASEDIR/..")"
|
||||
|
||||
function _fatal {
|
||||
echo -e "\e[31mERROR\e[0m $(</dev/stdin)$*" 1>&2
|
||||
exit 1
|
||||
}
|
||||
|
||||
declare -a PODMAN_ARGS=(
|
||||
"--rm" "-i" "--log-driver=none"
|
||||
"-v" "$PLANTCTL_PROJECT_DIR:$PLANTCTL_PROJECT_DIR:rw"
|
||||
"-v" "$PWD:$PWD:rw"
|
||||
"-w" "$PWD"
|
||||
)
|
||||
|
||||
[[ -t 1 ]] && PODMAN_ARGS+=("-t")
|
||||
|
||||
if ! podman image exists "$CONTAINER_IMAGE"; then
|
||||
#attempt to build container
|
||||
"$CONTAINER_TOOLS_BASEDIR/build-esp-plant-dev-tools.sh" 1>&2 ||
|
||||
_fatal "faild to build local image, cannot continue! … please ensure you have an internet connection"
|
||||
fi
|
||||
|
||||
podman run "${PODMAN_ARGS[@]}" --entrypoint riscv-none-elf-gcc "$CONTAINER_IMAGE" "$@"
|
||||
4
rust/.idea/dictionaries/project.xml
generated
4
rust/.idea/dictionaries/project.xml
generated
@@ -1,14 +1,18 @@
|
||||
<component name="ProjectDictionaryState">
|
||||
<dictionary name="project">
|
||||
<words>
|
||||
<w>boardtest</w>
|
||||
<w>buildtime</w>
|
||||
<w>deepsleep</w>
|
||||
<w>githash</w>
|
||||
<w>lamptest</w>
|
||||
<w>lightstate</w>
|
||||
<w>mppt</w>
|
||||
<w>plantstate</w>
|
||||
<w>pumptest</w>
|
||||
<w>sntp</w>
|
||||
<w>vergen</w>
|
||||
<w>wifiscan</w>
|
||||
</words>
|
||||
</dictionary>
|
||||
</component>
|
||||
@@ -7,5 +7,6 @@
|
||||
</Languages>
|
||||
</inspection_tool>
|
||||
<inspection_tool class="Eslint" enabled="true" level="WARNING" enabled_by_default="true" />
|
||||
<inspection_tool class="NewCrateVersionAvailable" enabled="true" level="INFORMATION" enabled_by_default="true" />
|
||||
</profile>
|
||||
</component>
|
||||
2931
rust/Cargo.lock
generated
Normal file
2931
rust/Cargo.lock
generated
Normal file
File diff suppressed because it is too large
Load Diff
119
rust/Cargo.toml
119
rust/Cargo.toml
@@ -1,3 +1,4 @@
|
||||
|
||||
[package]
|
||||
edition = "2021"
|
||||
name = "plant-ctrl2"
|
||||
@@ -26,99 +27,74 @@ command = [
|
||||
"partitions.csv"
|
||||
]
|
||||
|
||||
#this strips the bootloader, we need that tho
|
||||
#strip = true
|
||||
|
||||
[profile.dev]
|
||||
lto = "fat"
|
||||
strip = true
|
||||
debug = false
|
||||
overflow-checks = true
|
||||
panic = "abort"
|
||||
incremental = true
|
||||
opt-level = "z"
|
||||
|
||||
[profile.release]
|
||||
lto = "fat"
|
||||
#debug = false
|
||||
overflow-checks = true
|
||||
panic = "abort"
|
||||
incremental = false
|
||||
opt-level = "z"
|
||||
|
||||
[package.metadata.espflash]
|
||||
partition_table = "partitions.csv"
|
||||
|
||||
|
||||
[dependencies]
|
||||
#ESP stuff
|
||||
esp-bootloader-esp-idf = { version = "0.2.0", features = ["esp32c6"] }
|
||||
esp-hal = { version = "=1.0.0-rc.0", features = [
|
||||
"esp32c6",
|
||||
"log-04",
|
||||
"unstable",
|
||||
"rt"
|
||||
] }
|
||||
log = "0.4.27"
|
||||
log = "0.4.28"
|
||||
esp-bootloader-esp-idf = { version = "0.5.0", features = ["esp32c6", "log-04"] }
|
||||
esp-hal = { version = "1.1.0", features = ["esp32c6", "log-04"] }
|
||||
esp-rtos = { version = "0.3.0", features = ["esp32c6", "embassy", "esp-radio"] }
|
||||
esp-backtrace = { version = "0.19.0", features = ["esp32c6", "panic-handler", "println", "colors", "custom-halt"] }
|
||||
esp-println = { version = "0.17.0", features = ["esp32c6", "log-04", "auto"] }
|
||||
esp-storage = { version = "0.9.0", features = ["esp32c6"] }
|
||||
esp-radio = { version = "0.18.0", features = ["esp32c6", "log-04", "wifi", "unstable"] }
|
||||
esp-alloc = { version = "0.10.0", features = ["esp32c6", "internal-heap-stats"] }
|
||||
|
||||
embassy-net = { version = "0.7.1", default-features = false, features = [
|
||||
"dhcpv4",
|
||||
"log",
|
||||
"medium-ethernet",
|
||||
"tcp",
|
||||
"udp",
|
||||
] }
|
||||
embedded-io = "0.6.1"
|
||||
embedded-io-async = "0.6.1"
|
||||
esp-alloc = "0.8.0"
|
||||
esp-backtrace = { version = "0.17.0", features = [
|
||||
"esp32c6",
|
||||
"exception-handler",
|
||||
"panic-handler",
|
||||
"println",
|
||||
"colors",
|
||||
"custom-halt"
|
||||
] }
|
||||
esp-println = { version = "0.15.0", features = ["esp32c6", "log-04"] }
|
||||
# for more networking protocol support see https://crates.io/crates/edge-net
|
||||
embassy-executor = { version = "0.7.0", features = [
|
||||
"log",
|
||||
"task-arena-size-64",
|
||||
"nightly"
|
||||
] }
|
||||
embassy-time = { version = "0.5.0", features = ["log"], default-features = false }
|
||||
esp-hal-embassy = { version = "0.9.0", features = ["esp32c6", "log-04"] }
|
||||
esp-storage = { version = "0.7.0", features = ["esp32c6"] }
|
||||
# Async runtime (Embassy core)
|
||||
embassy-executor = { version = "0.10.0", features = ["log", "nightly"] }
|
||||
embassy-time = { version = "0.5.1", features = ["log"], default-features = false }
|
||||
embassy-sync = { version = "0.8.0", features = ["log"] }
|
||||
|
||||
esp-wifi = { version = "0.15.0", features = [
|
||||
"builtin-scheduler",
|
||||
"esp-alloc",
|
||||
"esp32c6",
|
||||
"log-04",
|
||||
"smoltcp",
|
||||
"wifi",
|
||||
] }
|
||||
smoltcp = { version = "0.12.0", default-features = false, features = [
|
||||
"alloc",
|
||||
"log",
|
||||
"medium-ethernet",
|
||||
"multicast",
|
||||
"proto-dhcpv4",
|
||||
"proto-dns",
|
||||
"proto-ipv4",
|
||||
"socket-dns",
|
||||
"socket-icmp",
|
||||
"socket-raw",
|
||||
"socket-tcp",
|
||||
"socket-udp",
|
||||
] }
|
||||
#static_cell = "2.1.1"
|
||||
# Networking and protocol stacks
|
||||
embassy-net = { version = "0.8.0", features = ["dhcpv4", "log", "medium-ethernet", "tcp", "udp", "proto-ipv4", "dns", "proto-ipv6"] }
|
||||
sntpc = { version = "0.6.1", default-features = false, features = ["log", "embassy-socket", "embassy-socket-ipv6"] }
|
||||
edge-dhcp = "0.7.0"
|
||||
edge-nal = "0.6.0"
|
||||
edge-nal-embassy = "0.8.1"
|
||||
edge-http = { version = "0.7.0", features = ["log"] }
|
||||
|
||||
esp32c6 = { version = "0.23.2" }
|
||||
|
||||
# Hardware abstraction traits and HAL adapters
|
||||
embedded-hal = "1.0.0"
|
||||
heapless = { version = "0.8", features = ["serde"] }
|
||||
embedded-hal-bus = { version = "0.3.0" }
|
||||
embedded-storage = "0.3.1"
|
||||
embassy-embedded-hal = "0.6.0"
|
||||
nb = "1.1.0"
|
||||
|
||||
#Hardware additional driver
|
||||
|
||||
#bq34z100 = { version = "0.3.0", default-features = false }
|
||||
lib-bms-protocol = { git = "https://gitea.wlandt.de/judge/ch32-bms.git", default-features = false }
|
||||
onewire = "0.4.0"
|
||||
#strum = { version = "0.27.0", default-feature = false, features = ["derive"] }
|
||||
measurements = "0.11.0"
|
||||
ds323x = "0.6.0"
|
||||
|
||||
#json
|
||||
serde = { version = "1.0.219", features = ["derive", "alloc"], default-features = false }
|
||||
serde_json = { version = "1.0.143", default-features = false, features = ["alloc"] }
|
||||
|
||||
#timezone
|
||||
chrono = { version = "0.4.42", default-features = false, features = ["iana-time-zone", "alloc", "serde"] }
|
||||
chrono-tz = { version = "0.10.4", default-features = false, features = ["filter-by-regex"] }
|
||||
eeprom24x = "0.7.2"
|
||||
@@ -127,24 +103,21 @@ strum_macros = "0.27.0"
|
||||
unit-enum = "1.4.1"
|
||||
pca9535 = { version = "2.0.0" }
|
||||
ina219 = { version = "0.2.0" }
|
||||
embedded-storage = "=0.3.1"
|
||||
ekv = "1.0.0"
|
||||
embedded-can = "0.4.1"
|
||||
portable-atomic = "1.11.1"
|
||||
embassy-sync = { version = "0.7.2", features = ["log"] }
|
||||
async-trait = "0.1.89"
|
||||
bq34z100 = { version = "0.4.0", default-features = false }
|
||||
edge-dhcp = "0.6.0"
|
||||
edge-nal = "0.5.0"
|
||||
edge-nal-embassy = "0.6.0"
|
||||
static_cell = "2.1.1"
|
||||
edge-http = { version = "0.6.1", features = ["log"] }
|
||||
littlefs2 = { version = "0.6.1", features = ["c-stubs", "alloc"] }
|
||||
littlefs2-core = "0.1.1"
|
||||
bytemuck = { version = "1.23.2", features = ["derive", "min_const_generics", "pod_saturating", "extern_crate_alloc"] }
|
||||
deranged = "0.5.3"
|
||||
embassy-embedded-hal = "0.5.0"
|
||||
bincode = { version = "2.0.1", default-features = false, features = ["derive"] }
|
||||
option-lock = { version = "0.3.1", default-features = false }
|
||||
measurements = "0.11.1"
|
||||
heapless = { version = "0.7.17", features = ["serde"] }
|
||||
mcutie = { path = "./src/mcutie_3_0_0/", default-features = false, features = ["log"] }
|
||||
|
||||
|
||||
|
||||
[patch.crates-io]
|
||||
#bq34z100 = { path = "../../bq34z100_rust" }
|
||||
|
||||
BIN
rust/bootloader.bin
Normal file
BIN
rust/bootloader.bin
Normal file
Binary file not shown.
@@ -1,434 +0,0 @@
|
||||
use crate::hal::rtc::RTCModuleInteraction;
|
||||
use crate::hal::water::TankSensor;
|
||||
use crate::hal::{
|
||||
deep_sleep, BoardInteraction, FreePeripherals, Sensor, PLANT_COUNT,
|
||||
};
|
||||
use crate::log::{log, LogMessage};
|
||||
use crate::{
|
||||
config::PlantControllerConfig,
|
||||
hal::{battery::BatteryInteraction, esp::Esp},
|
||||
};
|
||||
use anyhow::{bail, Ok, Result};
|
||||
use embedded_hal::digital::OutputPin;
|
||||
use measurements::{Current, Voltage};
|
||||
use plant_ctrl2::sipo::ShiftRegister40;
|
||||
use core::result::Result::Ok as OkStd;
|
||||
use alloc::string::ToString;
|
||||
use alloc::boxed::Box;
|
||||
use esp_hall::gpio::Pull;
|
||||
|
||||
const PUMP8_BIT: usize = 0;
|
||||
const PUMP1_BIT: usize = 1;
|
||||
const PUMP2_BIT: usize = 2;
|
||||
const PUMP3_BIT: usize = 3;
|
||||
const PUMP4_BIT: usize = 4;
|
||||
const PUMP5_BIT: usize = 5;
|
||||
const PUMP6_BIT: usize = 6;
|
||||
const PUMP7_BIT: usize = 7;
|
||||
const MS_0: usize = 8;
|
||||
const MS_4: usize = 9;
|
||||
const MS_2: usize = 10;
|
||||
const MS_3: usize = 11;
|
||||
const MS_1: usize = 13;
|
||||
const SENSOR_ON: usize = 12;
|
||||
|
||||
const SENSOR_A_1: u8 = 7;
|
||||
const SENSOR_A_2: u8 = 6;
|
||||
const SENSOR_A_3: u8 = 5;
|
||||
const SENSOR_A_4: u8 = 4;
|
||||
const SENSOR_A_5: u8 = 3;
|
||||
const SENSOR_A_6: u8 = 2;
|
||||
const SENSOR_A_7: u8 = 1;
|
||||
const SENSOR_A_8: u8 = 0;
|
||||
|
||||
const SENSOR_B_1: u8 = 8;
|
||||
const SENSOR_B_2: u8 = 9;
|
||||
const SENSOR_B_3: u8 = 10;
|
||||
const SENSOR_B_4: u8 = 11;
|
||||
const SENSOR_B_5: u8 = 12;
|
||||
const SENSOR_B_6: u8 = 13;
|
||||
const SENSOR_B_7: u8 = 14;
|
||||
const SENSOR_B_8: u8 = 15;
|
||||
|
||||
const CHARGING: usize = 14;
|
||||
const AWAKE: usize = 15;
|
||||
|
||||
const FAULT_3: usize = 16;
|
||||
const FAULT_8: usize = 17;
|
||||
const FAULT_7: usize = 18;
|
||||
const FAULT_6: usize = 19;
|
||||
const FAULT_5: usize = 20;
|
||||
const FAULT_4: usize = 21;
|
||||
const FAULT_1: usize = 22;
|
||||
const FAULT_2: usize = 23;
|
||||
|
||||
const REPEAT_MOIST_MEASURE: usize = 1;
|
||||
|
||||
|
||||
pub struct V3<'a> {
|
||||
config: PlantControllerConfig,
|
||||
battery_monitor: Box<dyn BatteryInteraction + Send>,
|
||||
rtc_module: Box<dyn RTCModuleInteraction + Send>,
|
||||
esp: Esp<'a>,
|
||||
shift_register: ShiftRegister40<
|
||||
PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
>,
|
||||
_shift_register_enable_invert:
|
||||
PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, esp_idf_hal::gpio::Output>,
|
||||
tank_sensor: TankSensor<'a>,
|
||||
solar_is_day: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, esp_idf_hal::gpio::Input>,
|
||||
light: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
main_pump: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
general_fault: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
|
||||
signal_counter: PcntDriver<'a>,
|
||||
}
|
||||
|
||||
pub(crate) fn create_v3(
|
||||
peripherals: FreePeripherals,
|
||||
esp: Esp<'static>,
|
||||
config: PlantControllerConfig,
|
||||
battery_monitor: Box<dyn BatteryInteraction + Send>,
|
||||
rtc_module: Box<dyn RTCModuleInteraction + Send>,
|
||||
) -> Result<Box<dyn BoardInteraction<'static> + Send>> {
|
||||
log::info!("Start v3");
|
||||
let mut clock = PinDriver::input_output(peripherals.gpio15.downgrade())?;
|
||||
clock.set_pull(Pull::Floating)?;
|
||||
let mut latch = PinDriver::input_output(peripherals.gpio3.downgrade())?;
|
||||
latch.set_pull(Pull::Floating)?;
|
||||
let mut data = PinDriver::input_output(peripherals.gpio23.downgrade())?;
|
||||
data.set_pull(Pull::Floating)?;
|
||||
let shift_register = ShiftRegister40::new(clock, latch, data);
|
||||
//disable all
|
||||
for mut pin in shift_register.decompose() {
|
||||
pin.set_low()?;
|
||||
}
|
||||
|
||||
let awake = &mut shift_register.decompose()[AWAKE];
|
||||
awake.set_high()?;
|
||||
|
||||
let charging = &mut shift_register.decompose()[CHARGING];
|
||||
charging.set_high()?;
|
||||
|
||||
let ms0 = &mut shift_register.decompose()[MS_0];
|
||||
ms0.set_low()?;
|
||||
let ms1 = &mut shift_register.decompose()[MS_1];
|
||||
ms1.set_low()?;
|
||||
let ms2 = &mut shift_register.decompose()[MS_2];
|
||||
ms2.set_low()?;
|
||||
let ms3 = &mut shift_register.decompose()[MS_3];
|
||||
ms3.set_low()?;
|
||||
|
||||
let ms4 = &mut shift_register.decompose()[MS_4];
|
||||
ms4.set_high()?;
|
||||
|
||||
let one_wire_pin = peripherals.gpio18.downgrade();
|
||||
let tank_power_pin = peripherals.gpio11.downgrade();
|
||||
|
||||
let flow_sensor_pin = peripherals.gpio4.downgrade();
|
||||
|
||||
let tank_sensor = TankSensor::create(
|
||||
one_wire_pin,
|
||||
peripherals.adc1,
|
||||
peripherals.gpio5,
|
||||
tank_power_pin,
|
||||
flow_sensor_pin,
|
||||
peripherals.pcnt1,
|
||||
)?;
|
||||
|
||||
let mut signal_counter = PcntDriver::new(
|
||||
peripherals.pcnt0,
|
||||
Some(peripherals.gpio22),
|
||||
Option::<AnyInputPin>::None,
|
||||
Option::<AnyInputPin>::None,
|
||||
Option::<AnyInputPin>::None,
|
||||
)?;
|
||||
|
||||
signal_counter.channel_config(
|
||||
PcntChannel::Channel0,
|
||||
PinIndex::Pin0,
|
||||
PinIndex::Pin1,
|
||||
&PcntChannelConfig {
|
||||
lctrl_mode: PcntControlMode::Keep,
|
||||
hctrl_mode: PcntControlMode::Keep,
|
||||
pos_mode: PcntCountMode::Increment,
|
||||
neg_mode: PcntCountMode::Hold,
|
||||
counter_h_lim: i16::MAX,
|
||||
counter_l_lim: 0,
|
||||
},
|
||||
)?;
|
||||
|
||||
let mut solar_is_day = PinDriver::input(peripherals.gpio7.downgrade())?;
|
||||
solar_is_day.set_pull(Pull::Floating)?;
|
||||
|
||||
let mut light = PinDriver::input_output(peripherals.gpio10.downgrade())?;
|
||||
light.set_pull(Pull::Floating)?;
|
||||
|
||||
let mut main_pump = PinDriver::input_output(peripherals.gpio2.downgrade())?;
|
||||
main_pump.set_pull(Pull::Floating)?;
|
||||
main_pump.set_low()?;
|
||||
|
||||
let mut general_fault = PinDriver::input_output(peripherals.gpio6.downgrade())?;
|
||||
general_fault.set_pull(Pull::Floating)?;
|
||||
general_fault.set_low()?;
|
||||
|
||||
let mut shift_register_enable_invert = PinDriver::output(peripherals.gpio21.downgrade())?;
|
||||
|
||||
unsafe { gpio_hold_dis(shift_register_enable_invert.pin()) };
|
||||
shift_register_enable_invert.set_low()?;
|
||||
unsafe { gpio_hold_en(shift_register_enable_invert.pin()) };
|
||||
|
||||
Ok(Box::new(V3 {
|
||||
config,
|
||||
battery_monitor,
|
||||
rtc_module,
|
||||
esp,
|
||||
shift_register,
|
||||
_shift_register_enable_invert: shift_register_enable_invert,
|
||||
tank_sensor,
|
||||
solar_is_day,
|
||||
light,
|
||||
main_pump,
|
||||
general_fault,
|
||||
signal_counter,
|
||||
}))
|
||||
}
|
||||
|
||||
impl<'a> BoardInteraction<'a> for V3<'a> {
|
||||
fn get_tank_sensor(&mut self) -> Option<&mut TankSensor<'a>> {
|
||||
Some(&mut self.tank_sensor)
|
||||
}
|
||||
|
||||
fn get_esp(&mut self) -> &mut Esp<'a> {
|
||||
&mut self.esp
|
||||
}
|
||||
|
||||
fn get_config(&mut self) -> &PlantControllerConfig {
|
||||
&self.config
|
||||
}
|
||||
|
||||
fn get_battery_monitor(&mut self) -> &mut Box<dyn BatteryInteraction + Send + 'static> {
|
||||
&mut self.battery_monitor
|
||||
}
|
||||
|
||||
fn get_rtc_module(&mut self) -> &mut Box<dyn RTCModuleInteraction + Send> {
|
||||
&mut self.rtc_module
|
||||
}
|
||||
fn set_charge_indicator(&mut self, charging: bool) -> Result<()> {
|
||||
Ok(self.shift_register.decompose()[CHARGING].set_state(charging.into())?)
|
||||
}
|
||||
|
||||
fn deep_sleep(&mut self, duration_in_ms: u64) -> ! {
|
||||
let _ = self.shift_register.decompose()[AWAKE].set_low();
|
||||
deep_sleep(duration_in_ms)
|
||||
}
|
||||
|
||||
fn is_day(&self) -> bool {
|
||||
self.solar_is_day.get_level().into()
|
||||
}
|
||||
|
||||
fn light(&mut self, enable: bool) -> Result<()> {
|
||||
unsafe { gpio_hold_dis(self.light.pin()) };
|
||||
self.light.set_state(enable.into())?;
|
||||
unsafe { gpio_hold_en(self.light.pin()) };
|
||||
Ok(())
|
||||
}
|
||||
fn pump(&mut self, plant: usize, enable: bool) -> Result<()> {
|
||||
if enable {
|
||||
self.main_pump.set_high()?;
|
||||
}
|
||||
|
||||
let index = match plant {
|
||||
0 => PUMP1_BIT,
|
||||
1 => PUMP2_BIT,
|
||||
2 => PUMP3_BIT,
|
||||
3 => PUMP4_BIT,
|
||||
4 => PUMP5_BIT,
|
||||
5 => PUMP6_BIT,
|
||||
6 => PUMP7_BIT,
|
||||
7 => PUMP8_BIT,
|
||||
_ => bail!("Invalid pump {plant}",),
|
||||
};
|
||||
self.shift_register.decompose()[index].set_state(enable.into())?;
|
||||
|
||||
if !enable {
|
||||
self.main_pump.set_low()?;
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
fn pump_current(&mut self, _plant: usize) -> Result<Current> {
|
||||
bail!("Not implemented in v3")
|
||||
}
|
||||
|
||||
fn fault(&mut self, plant: usize, enable: bool) -> Result<()> {
|
||||
let index = match plant {
|
||||
0 => FAULT_1,
|
||||
1 => FAULT_2,
|
||||
2 => FAULT_3,
|
||||
3 => FAULT_4,
|
||||
4 => FAULT_5,
|
||||
5 => FAULT_6,
|
||||
6 => FAULT_7,
|
||||
7 => FAULT_8,
|
||||
_ => panic!("Invalid plant id {}", plant),
|
||||
};
|
||||
self.shift_register.decompose()[index].set_state(enable.into())?;
|
||||
Ok(())
|
||||
}
|
||||
|
||||
fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> Result<f32> {
|
||||
let mut results = [0_f32; REPEAT_MOIST_MEASURE];
|
||||
for repeat in 0..REPEAT_MOIST_MEASURE {
|
||||
self.signal_counter.counter_pause()?;
|
||||
self.signal_counter.counter_clear()?;
|
||||
//Disable all
|
||||
self.shift_register.decompose()[MS_4].set_high()?;
|
||||
|
||||
let sensor_channel = match sensor {
|
||||
Sensor::A => match plant {
|
||||
0 => SENSOR_A_1,
|
||||
1 => SENSOR_A_2,
|
||||
2 => SENSOR_A_3,
|
||||
3 => SENSOR_A_4,
|
||||
4 => SENSOR_A_5,
|
||||
5 => SENSOR_A_6,
|
||||
6 => SENSOR_A_7,
|
||||
7 => SENSOR_A_8,
|
||||
_ => bail!("Invalid plant id {}", plant),
|
||||
},
|
||||
Sensor::B => match plant {
|
||||
0 => SENSOR_B_1,
|
||||
1 => SENSOR_B_2,
|
||||
2 => SENSOR_B_3,
|
||||
3 => SENSOR_B_4,
|
||||
4 => SENSOR_B_5,
|
||||
5 => SENSOR_B_6,
|
||||
6 => SENSOR_B_7,
|
||||
7 => SENSOR_B_8,
|
||||
_ => bail!("Invalid plant id {}", plant),
|
||||
},
|
||||
};
|
||||
|
||||
let is_bit_set = |b: u8| -> bool { sensor_channel & (1 << b) != 0 };
|
||||
let pin_0 = &mut self.shift_register.decompose()[MS_0];
|
||||
let pin_1 = &mut self.shift_register.decompose()[MS_1];
|
||||
let pin_2 = &mut self.shift_register.decompose()[MS_2];
|
||||
let pin_3 = &mut self.shift_register.decompose()[MS_3];
|
||||
if is_bit_set(0) {
|
||||
pin_0.set_high()?;
|
||||
} else {
|
||||
pin_0.set_low()?;
|
||||
}
|
||||
if is_bit_set(1) {
|
||||
pin_1.set_high()?;
|
||||
} else {
|
||||
pin_1.set_low()?;
|
||||
}
|
||||
if is_bit_set(2) {
|
||||
pin_2.set_high()?;
|
||||
} else {
|
||||
pin_2.set_low()?;
|
||||
}
|
||||
if is_bit_set(3) {
|
||||
pin_3.set_high()?;
|
||||
} else {
|
||||
pin_3.set_low()?;
|
||||
}
|
||||
|
||||
self.shift_register.decompose()[MS_4].set_low()?;
|
||||
self.shift_register.decompose()[SENSOR_ON].set_high()?;
|
||||
|
||||
let measurement = 100; //how long to measure and then extrapolate to hz
|
||||
let factor = 1000f32 / measurement as f32; //scale raw cound by this number to get hz
|
||||
|
||||
//give some time to stabilize
|
||||
self.esp.delay.delay_ms(10);
|
||||
self.signal_counter.counter_resume()?;
|
||||
self.esp.delay.delay_ms(measurement);
|
||||
self.signal_counter.counter_pause()?;
|
||||
self.shift_register.decompose()[MS_4].set_high()?;
|
||||
self.shift_register.decompose()[SENSOR_ON].set_low()?;
|
||||
self.esp.delay.delay_ms(10);
|
||||
let unscaled = self.signal_counter.get_counter_value()? as i32;
|
||||
let hz = unscaled as f32 * factor;
|
||||
log(
|
||||
LogMessage::RawMeasure,
|
||||
unscaled as u32,
|
||||
hz as u32,
|
||||
&plant.to_string(),
|
||||
&format!("{sensor:?}"),
|
||||
);
|
||||
results[repeat] = hz;
|
||||
}
|
||||
results.sort_by(|a, b| a.partial_cmp(b).unwrap()); // floats don't seem to implement total_ord
|
||||
|
||||
let mid = results.len() / 2;
|
||||
let median = results[mid];
|
||||
Ok(median)
|
||||
}
|
||||
|
||||
fn general_fault(&mut self, enable: bool) {
|
||||
unsafe { gpio_hold_dis(self.general_fault.pin()) };
|
||||
self.general_fault.set_state(enable.into()).unwrap();
|
||||
unsafe { gpio_hold_en(self.general_fault.pin()) };
|
||||
}
|
||||
|
||||
fn test(&mut self) -> Result<()> {
|
||||
self.general_fault(true);
|
||||
self.esp.delay.delay_ms(100);
|
||||
self.general_fault(false);
|
||||
self.esp.delay.delay_ms(100);
|
||||
self.light(true)?;
|
||||
self.esp.delay.delay_ms(500);
|
||||
self.light(false)?;
|
||||
self.esp.delay.delay_ms(500);
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.fault(i, true)?;
|
||||
self.esp.delay.delay_ms(500);
|
||||
self.fault(i, false)?;
|
||||
self.esp.delay.delay_ms(500);
|
||||
}
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.pump(i, true)?;
|
||||
self.esp.delay.delay_ms(100);
|
||||
self.pump(i, false)?;
|
||||
self.esp.delay.delay_ms(100);
|
||||
}
|
||||
for plant in 0..PLANT_COUNT {
|
||||
let a = self.measure_moisture_hz(plant, Sensor::A);
|
||||
let b = self.measure_moisture_hz(plant, Sensor::B);
|
||||
let aa = match a {
|
||||
OkStd(a) => a as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
let bb = match b {
|
||||
OkStd(b) => b as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
log(LogMessage::TestSensor, aa, bb, &plant.to_string(), "");
|
||||
}
|
||||
self.esp.delay.delay_ms(10);
|
||||
Ok(())
|
||||
}
|
||||
|
||||
fn set_config(&mut self, config: PlantControllerConfig) -> Result<()> {
|
||||
self.config = config;
|
||||
self.esp.save_config(&self.config)?;
|
||||
anyhow::Ok(())
|
||||
}
|
||||
|
||||
fn get_mptt_voltage(&mut self) -> Result<Voltage> {
|
||||
//assuming module to work, these are the hardware set values
|
||||
if self.is_day() {
|
||||
Ok(Voltage::from_volts(15_f64))
|
||||
} else {
|
||||
Ok(Voltage::from_volts(0_f64))
|
||||
}
|
||||
}
|
||||
|
||||
fn get_mptt_current(&mut self) -> Result<Current> {
|
||||
bail!("Board does not have current sensor")
|
||||
}
|
||||
}
|
||||
@@ -1,7 +1,7 @@
|
||||
use alloc::string::String;
|
||||
use core::str::FromStr;
|
||||
use crate::hal::PLANT_COUNT;
|
||||
use crate::plant_state::PlantWateringMode;
|
||||
use alloc::string::String;
|
||||
use core::str::FromStr;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[derive(Serialize, Deserialize, Clone, Debug, PartialEq)]
|
||||
@@ -10,10 +10,10 @@ pub struct NetworkConfig {
|
||||
pub ap_ssid: heapless::String<32>,
|
||||
pub ssid: Option<heapless::String<32>>,
|
||||
pub password: Option<heapless::String<64>>,
|
||||
pub mqtt_url: Option<heapless::String<128>>,
|
||||
pub mqtt_url: Option<String>,
|
||||
pub base_topic: Option<heapless::String<64>>,
|
||||
pub mqtt_user: Option<heapless::String<32>>,
|
||||
pub mqtt_password: Option<heapless::String<64>>,
|
||||
pub mqtt_user: Option<String>,
|
||||
pub mqtt_password: Option<String>,
|
||||
pub max_wait: u32,
|
||||
}
|
||||
impl Default for NetworkConfig {
|
||||
|
||||
@@ -7,7 +7,8 @@ use embassy_embedded_hal::shared_bus::I2cDeviceError;
|
||||
use embassy_executor::SpawnError;
|
||||
use embassy_sync::mutex::TryLockError;
|
||||
use esp_hal::i2c::master::ConfigError;
|
||||
use esp_wifi::wifi::WifiError;
|
||||
use esp_hal::pcnt::unit::{InvalidHighLimit, InvalidLowLimit};
|
||||
use esp_radio::wifi::WifiError;
|
||||
use ina219::errors::{BusVoltageReadError, ShuntVoltageReadError};
|
||||
use littlefs2_core::PathError;
|
||||
use onewire::Error;
|
||||
@@ -44,6 +45,7 @@ pub enum FatError {
|
||||
SpawnError {
|
||||
error: SpawnError,
|
||||
},
|
||||
OTAError,
|
||||
PartitionError {
|
||||
error: esp_bootloader_esp_idf::partitions::Error,
|
||||
},
|
||||
@@ -59,6 +61,9 @@ pub enum FatError {
|
||||
ExpanderError {
|
||||
error: String,
|
||||
},
|
||||
SNTPError {
|
||||
error: sntpc::Error,
|
||||
},
|
||||
}
|
||||
|
||||
pub type FatResult<T> = Result<T, FatError>;
|
||||
@@ -87,6 +92,10 @@ impl fmt::Display for FatError {
|
||||
FatError::DS323 { error } => write!(f, "DS323 {:?}", error),
|
||||
FatError::Eeprom24x { error } => write!(f, "Eeprom24x {:?}", error),
|
||||
FatError::ExpanderError { error } => write!(f, "ExpanderError {:?}", error),
|
||||
FatError::SNTPError { error } => write!(f, "SNTPError {error:?}"),
|
||||
FatError::OTAError => {
|
||||
write!(f, "OTA missing partition")
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -126,6 +135,24 @@ impl<T> ContextExt<T> for Option<T> {
|
||||
}
|
||||
}
|
||||
|
||||
impl<T, E> ContextExt<T> for Result<T, E>
|
||||
where
|
||||
E: fmt::Debug,
|
||||
{
|
||||
fn context<C>(self, context: C) -> Result<T, FatError>
|
||||
where
|
||||
C: AsRef<str>,
|
||||
{
|
||||
match self {
|
||||
Ok(value) => Ok(value),
|
||||
Err(err) => Err(FatError::String {
|
||||
error: format!("{}: {:?}", context.as_ref(), err),
|
||||
}),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
impl From<Error<Infallible>> for FatError {
|
||||
fn from(error: Error<Infallible>) -> Self {
|
||||
FatError::OneWireError { error }
|
||||
@@ -167,6 +194,12 @@ impl From<SpawnError> for FatError {
|
||||
}
|
||||
}
|
||||
|
||||
impl From<sntpc::Error> for FatError {
|
||||
fn from(value: sntpc::Error) -> Self {
|
||||
FatError::SNTPError { error: value }
|
||||
}
|
||||
}
|
||||
|
||||
impl From<esp_bootloader_esp_idf::partitions::Error> for FatError {
|
||||
fn from(value: esp_bootloader_esp_idf::partitions::Error) -> Self {
|
||||
FatError::PartitionError { error: value }
|
||||
@@ -257,3 +290,32 @@ impl<E: core::fmt::Debug> From<ShuntVoltageReadError<I2cDeviceError<E>>> for Fat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl From<Infallible> for FatError {
|
||||
fn from(value: Infallible) -> Self {
|
||||
panic!("Infallible error: {:?}", value)
|
||||
}
|
||||
}
|
||||
|
||||
impl From<InvalidLowLimit> for FatError {
|
||||
fn from(value: InvalidLowLimit) -> Self {
|
||||
FatError::String {
|
||||
error: format!("{:?}", value),
|
||||
}
|
||||
}
|
||||
}
|
||||
impl From<InvalidHighLimit> for FatError {
|
||||
fn from(value: InvalidHighLimit) -> Self {
|
||||
FatError::String {
|
||||
error: format!("{:?}", value),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl From<chrono::format::ParseError> for FatError {
|
||||
fn from(value: chrono::format::ParseError) -> Self {
|
||||
FatError::String {
|
||||
error: format!("Parsing error: {value:?}"),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
use crate::hal::Box;
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::Box;
|
||||
use alloc::string::String;
|
||||
use async_trait::async_trait;
|
||||
use bq34z100::{Bq34z100g1, Bq34z100g1Driver, Flags};
|
||||
@@ -43,14 +43,6 @@ pub enum BatteryError {
|
||||
CommunicationError(String),
|
||||
}
|
||||
|
||||
// impl From<Bq34Z100Error<esp_idf_hal::i2c::I2cError>> for BatteryError {
|
||||
// fn from(err: Bq34Z100Error<esp_idf_hal::i2c::I2cError>) -> Self {
|
||||
// BatteryError::CommunicationError(
|
||||
// anyhow!("failed to communicate with battery monitor: {:?}", err).to_string(),
|
||||
// )
|
||||
// }
|
||||
// }
|
||||
|
||||
#[derive(Debug, Serialize)]
|
||||
pub enum BatteryState {
|
||||
Unknown,
|
||||
@@ -62,7 +54,8 @@ pub struct NoBatteryMonitor {}
|
||||
#[async_trait]
|
||||
impl BatteryInteraction for NoBatteryMonitor {
|
||||
async fn state_charge_percent(&mut self) -> FatResult<f32> {
|
||||
Err(FatError::NoBatteryMonitor)
|
||||
// No monitor configured: assume full battery for lightstate logic
|
||||
Ok(100.0)
|
||||
}
|
||||
|
||||
async fn remaining_milli_ampere_hour(&mut self) -> FatResult<u16> {
|
||||
|
||||
@@ -1,51 +1,64 @@
|
||||
use crate::bail;
|
||||
use crate::config::{NetworkConfig, PlantControllerConfig};
|
||||
use crate::hal::PLANT_COUNT;
|
||||
use crate::log::{LogMessage, LOG_ACCESS};
|
||||
use crate::log::{log, LogMessage};
|
||||
use alloc::vec;
|
||||
use chrono::{DateTime, Utc};
|
||||
use esp_hal::Blocking;
|
||||
use esp_hal::uart::Uart;
|
||||
use serde::Serialize;
|
||||
|
||||
use crate::hal::little_fs2storage_adapter::LittleFs2Filesystem;
|
||||
use crate::fat_error::{ContextExt, FatError, FatResult};
|
||||
use crate::hal::little_fs2storage_adapter::LittleFs2Filesystem;
|
||||
use alloc::string::ToString;
|
||||
use alloc::sync::Arc;
|
||||
use alloc::{format, string::String, vec::Vec};
|
||||
use alloc::borrow::ToOwned;
|
||||
use core::marker::PhantomData;
|
||||
use core::net::{IpAddr, Ipv4Addr};
|
||||
use core::net::{IpAddr, Ipv4Addr, SocketAddr};
|
||||
use core::str::FromStr;
|
||||
use core::sync::atomic::Ordering;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_net::{Ipv4Cidr, Runner, Stack, StackResources, StaticConfigV4};
|
||||
use embassy_net::{DhcpConfig, IpAddress, Ipv4Cidr, Runner, Stack, StackResources, StaticConfigV4};
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use embassy_time::{Duration, Timer};
|
||||
use embedded_storage::nor_flash::ReadNorFlash;
|
||||
use embassy_sync::mutex::{Mutex, MutexGuard};
|
||||
use embassy_time::{Duration, Timer, WithTimeout};
|
||||
use embedded_storage::nor_flash::{check_erase, NorFlash, ReadNorFlash, RmwNorFlashStorage};
|
||||
use esp_bootloader_esp_idf::ota::OtaImageState::Valid;
|
||||
use esp_bootloader_esp_idf::ota::{Ota, OtaImageState};
|
||||
use esp_bootloader_esp_idf::partitions::FlashRegion;
|
||||
use esp_hal::gpio::Input;
|
||||
use esp_bootloader_esp_idf::partitions::{AppPartitionSubType, FlashRegion};
|
||||
use esp_hal::gpio::{Input, RtcPinWithResistors};
|
||||
use esp_hal::rng::Rng;
|
||||
use esp_hal::rtc_cntl::sleep::RtcSleepConfig;
|
||||
use esp_hal::rtc_cntl::{
|
||||
sleep::{TimerWakeupSource, WakeupLevel},
|
||||
Rtc,
|
||||
};
|
||||
use esp_hal::system::software_reset;
|
||||
use esp_println::println;
|
||||
use esp_radio::wifi::ap::{AccessPointConfig, AccessPointInfo};
|
||||
use esp_radio::wifi::scan::{ScanConfig, ScanTypeConfig};
|
||||
use esp_radio::wifi::sta::StationConfig;
|
||||
use esp_radio::wifi::{AuthenticationMethod, Config, Interface, WifiController};
|
||||
use esp_storage::FlashStorage;
|
||||
use esp_wifi::wifi::{
|
||||
AccessPointConfiguration, AccessPointInfo, Configuration, Interfaces, ScanConfig,
|
||||
ScanTypeConfig, WifiController, WifiDevice,
|
||||
};
|
||||
use littlefs2::fs::Filesystem;
|
||||
use littlefs2_core::{FileType, PathBuf, SeekFrom};
|
||||
use log::info;
|
||||
use log::{info, warn, error};
|
||||
use portable_atomic::AtomicBool;
|
||||
|
||||
#[esp_hal::ram(rtc_fast, persistent)]
|
||||
use super::shared_flash::MutexFlashStorage;
|
||||
use crate::network::{net_task, run_dhcp};
|
||||
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut LAST_WATERING_TIMESTAMP: [i64; PLANT_COUNT] = [0; PLANT_COUNT];
|
||||
#[esp_hal::ram(rtc_fast, persistent)]
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut CONSECUTIVE_WATERING_PLANT: [u32; PLANT_COUNT] = [0; PLANT_COUNT];
|
||||
#[esp_hal::ram(rtc_fast, persistent)]
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut LOW_VOLTAGE_DETECTED: i8 = 0;
|
||||
#[esp_hal::ram(rtc_fast, persistent)]
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut RESTART_TO_CONF: i8 = 0;
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut LAST_CORROSION_PROTECTION_CHECK_DAY: i8 = -1;
|
||||
|
||||
static CONFIG_FILE: &str = "config.json";
|
||||
|
||||
const CONFIG_FILE: &str = "config.json";
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
pub struct FileInfo {
|
||||
@@ -60,31 +73,43 @@ pub struct FileList {
|
||||
files: Vec<FileInfo>,
|
||||
}
|
||||
|
||||
pub struct FileSystemSizeInfo {
|
||||
pub total_size: usize,
|
||||
pub used_size: usize,
|
||||
pub free_size: usize,
|
||||
// Minimal esp-idf equivalent for gpio_hold on esp32c6 via ROM functions
|
||||
extern "C" {
|
||||
fn gpio_pad_hold(gpio_num: u32);
|
||||
fn gpio_pad_unhold(gpio_num: u32);
|
||||
}
|
||||
|
||||
pub struct MqttClient<'a> {
|
||||
dummy: PhantomData<&'a ()>,
|
||||
//mqtt_client: EspMqttClient<'a>,
|
||||
base_topic: heapless::String<64>,
|
||||
#[inline(always)]
|
||||
pub fn hold_enable(gpio_num: u8) {
|
||||
unsafe { gpio_pad_hold(gpio_num as u32) }
|
||||
}
|
||||
|
||||
#[inline(always)]
|
||||
pub fn hold_disable(gpio_num: u8) {
|
||||
unsafe { gpio_pad_unhold(gpio_num as u32) }
|
||||
}
|
||||
|
||||
pub struct Esp<'a> {
|
||||
pub fs: Arc<Mutex<CriticalSectionRawMutex, Filesystem<'static, LittleFs2Filesystem>>>,
|
||||
pub rng: Rng,
|
||||
//first starter (ap or sta will take these)
|
||||
pub interfaces: Option<Interfaces<'static>>,
|
||||
pub interface_sta: Option<Interface<'static>>,
|
||||
pub interface_ap: Option<Interface<'static>>,
|
||||
pub controller: Arc<Mutex<CriticalSectionRawMutex, WifiController<'static>>>,
|
||||
|
||||
//only filled, if a useable mqtt client with working roundtrip could be established
|
||||
pub(crate) mqtt_client: Option<MqttClient<'a>>,
|
||||
|
||||
pub boot_button: Input<'a>,
|
||||
|
||||
pub ota: Ota<'static, FlashStorage>,
|
||||
pub ota_next: &'static mut FlashRegion<'static, FlashStorage>,
|
||||
// RTC-capable GPIO used as external wake source (store the raw peripheral)
|
||||
pub wake_gpio1: esp_hal::peripherals::GPIO1<'static>,
|
||||
pub uart0: Uart<'a, Blocking>,
|
||||
|
||||
pub rtc: Rtc<'a>,
|
||||
|
||||
pub ota: Ota<'static, RmwNorFlashStorage<'static, &'static mut MutexFlashStorage>>,
|
||||
pub ota_target: &'static mut FlashRegion<'static, MutexFlashStorage>,
|
||||
pub current: AppPartitionSubType,
|
||||
pub slot0_state: OtaImageState,
|
||||
pub slot1_state: OtaImageState,
|
||||
}
|
||||
|
||||
// SAFETY: On this target we never move Esp across OS threads; the firmware runs single-core
|
||||
@@ -95,24 +120,50 @@ pub struct Esp<'a> {
|
||||
// CPU cores/threads, reconsider this.
|
||||
unsafe impl Send for Esp<'_> {}
|
||||
|
||||
pub struct IpInfo {
|
||||
pub(crate) ip: IpAddr,
|
||||
netmask: IpAddr,
|
||||
gateway: IpAddr,
|
||||
}
|
||||
|
||||
macro_rules! mk_static {
|
||||
($t:ty,$val:expr) => {{
|
||||
static STATIC_CELL: static_cell::StaticCell<$t> = static_cell::StaticCell::new();
|
||||
#[deny(unused_attributes)]
|
||||
let x = STATIC_CELL.uninit().write(($val));
|
||||
x
|
||||
}};
|
||||
}
|
||||
|
||||
impl Esp<'_> {
|
||||
pub fn get_time(&self) -> DateTime<Utc> {
|
||||
DateTime::from_timestamp_micros(self.rtc.current_time_us() as i64)
|
||||
.unwrap_or(DateTime::UNIX_EPOCH)
|
||||
}
|
||||
|
||||
pub fn set_time(&mut self, time: DateTime<Utc>) {
|
||||
self.rtc.set_current_time_us(time.timestamp_micros() as u64);
|
||||
}
|
||||
|
||||
pub(crate) async fn read_serial_line(&mut self) -> FatResult<Option<alloc::string::String>> {
|
||||
let mut buf = [0u8; 1];
|
||||
let mut line = String::new();
|
||||
loop {
|
||||
match self.uart0.read_buffered(&mut buf) {
|
||||
Ok(read) => {
|
||||
if read == 0 {
|
||||
return Ok(None);
|
||||
}
|
||||
let c = buf[0] as char;
|
||||
if c == '\n' {
|
||||
return Ok(Some(line));
|
||||
}
|
||||
line.push(c);
|
||||
}
|
||||
Err(error) => {
|
||||
if line.is_empty() {
|
||||
return Ok(None);
|
||||
} else {
|
||||
error!("Error reading serial line: {error:?}");
|
||||
// If we already have some data, we should probably wait a bit or just return what we have?
|
||||
// But the protocol expects a full line or message.
|
||||
// For simplicity in config mode, we can block here or just return None if nothing is there yet.
|
||||
// However, if we started receiving, we should probably finish or timeout.
|
||||
continue;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
pub(crate) async fn delete_file(&self, filename: String) -> FatResult<()> {
|
||||
let file = PathBuf::try_from(filename.as_str()).unwrap();
|
||||
let file = PathBuf::try_from(filename.as_str())?;
|
||||
let access = self.fs.lock().await;
|
||||
access.remove(&*file)?;
|
||||
Ok(())
|
||||
@@ -175,26 +226,47 @@ impl Esp<'_> {
|
||||
Ok((buf, read))
|
||||
}
|
||||
|
||||
pub(crate) fn get_ota_slot(&mut self) -> String {
|
||||
match self.ota.current_slot() {
|
||||
Ok(slot) => {
|
||||
format!("{:?}", slot)
|
||||
}
|
||||
Err(err) => {
|
||||
format!("{:?}", err)
|
||||
}
|
||||
pub(crate) async fn write_ota(&mut self, offset: u32, buf: &[u8]) -> Result<(), FatError> {
|
||||
let _ = check_erase(self.ota_target, offset, offset + 4096);
|
||||
info!("erasing and writing block 0x{offset:x}");
|
||||
self.ota_target.erase(offset, offset + 4096)?;
|
||||
|
||||
let mut temp = vec![0; buf.len()];
|
||||
let read_back = temp.as_mut_slice();
|
||||
//change to nor flash, align writes!
|
||||
self.ota_target.write(offset, buf)?;
|
||||
self.ota_target.read(offset, read_back)?;
|
||||
if buf != read_back {
|
||||
info!("Expected {buf:?} but got {read_back:?}");
|
||||
bail!(
|
||||
"Flash error, read back does not match write buffer at offset {:x}",
|
||||
offset
|
||||
)
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
pub(crate) fn get_ota_state(&mut self) -> String {
|
||||
match self.ota.current_ota_state() {
|
||||
Ok(state) => {
|
||||
format!("{:?}", state)
|
||||
}
|
||||
Err(err) => {
|
||||
format!("{:?}", err)
|
||||
}
|
||||
pub(crate) async fn finalize_ota(&mut self) -> Result<(), FatError> {
|
||||
let current = self.ota.current_app_partition()?;
|
||||
if self.ota.current_ota_state()? != Valid {
|
||||
info!("Validating current slot {current:?} as it was able to ota");
|
||||
self.ota.set_current_ota_state(Valid)?;
|
||||
}
|
||||
let next = match current {
|
||||
AppPartitionSubType::Ota0 => AppPartitionSubType::Ota1,
|
||||
AppPartitionSubType::Ota1 => AppPartitionSubType::Ota0,
|
||||
_ => {
|
||||
bail!("Invalid current slot {current:?} for ota");
|
||||
}
|
||||
};
|
||||
self.ota.set_current_app_partition(next)?;
|
||||
info!("switched slot");
|
||||
self.ota.set_current_ota_state(OtaImageState::New)?;
|
||||
info!("switched state for new partition");
|
||||
let state_new = self.ota.current_ota_state()?;
|
||||
info!("state on new partition now {state_new:?}");
|
||||
self.set_restart_to_conf(true);
|
||||
Ok(())
|
||||
}
|
||||
|
||||
// let current = ota.current_slot()?;
|
||||
@@ -208,38 +280,16 @@ impl Esp<'_> {
|
||||
pub(crate) fn mode_override_pressed(&mut self) -> bool {
|
||||
self.boot_button.is_low()
|
||||
}
|
||||
pub(crate) async fn sntp(&mut self, _max_wait_ms: u32) -> FatResult<DateTime<Utc>> {
|
||||
//let sntp = sntp::EspSntp::new_default()?;
|
||||
//let mut counter = 0;
|
||||
//while sntp.get_sync_status() != SyncStatus::Completed {
|
||||
// self.delay.delay_ms(100);
|
||||
// counter += 100;
|
||||
// if counter > max_wait_ms {
|
||||
// bail!("Reached sntp timeout, aborting")
|
||||
// }
|
||||
//}
|
||||
//self.time()
|
||||
todo!();
|
||||
}
|
||||
|
||||
pub async fn flash_ota(&mut self) -> FatResult<()> {
|
||||
let capacity = self.ota_next.capacity();
|
||||
|
||||
bail!("not implemented")
|
||||
}
|
||||
|
||||
pub(crate) async fn wifi_scan(&mut self) -> FatResult<Vec<AccessPointInfo>> {
|
||||
info!("start wifi scan");
|
||||
let mut lock = self.controller.try_lock()?;
|
||||
info!("start wifi scan lock");
|
||||
let scan_config = ScanConfig {
|
||||
ssid: None,
|
||||
bssid: None,
|
||||
channel: None,
|
||||
show_hidden: false,
|
||||
scan_type: ScanTypeConfig::Passive(core::time::Duration::from_secs(2)),
|
||||
};
|
||||
let rv = lock.scan_with_config_async(scan_config).await?;
|
||||
let scan_config = ScanConfig::default().with_scan_type(ScanTypeConfig::Active {
|
||||
min: esp_hal::time::Duration::from_millis(0),
|
||||
max: esp_hal::time::Duration::from_millis(0),
|
||||
});
|
||||
let rv = lock.scan_async(&scan_config).await?;
|
||||
info!("end wifi scan lock");
|
||||
Ok(rv)
|
||||
}
|
||||
@@ -260,7 +310,7 @@ impl Esp<'_> {
|
||||
}
|
||||
pub(crate) fn clear_low_voltage_in_cycle(&mut self) {
|
||||
unsafe {
|
||||
LOW_VOLTAGE_DETECTED = 1;
|
||||
LOW_VOLTAGE_DETECTED = 0;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -288,158 +338,30 @@ impl Esp<'_> {
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn wifi_ap(&mut self) -> FatResult<Stack<'static>> {
|
||||
let ssid = match self.load_config().await {
|
||||
Ok(config) => config.network.ap_ssid.as_str().to_string(),
|
||||
Err(_) => "PlantCtrl Emergency Mode".to_string(),
|
||||
};
|
||||
|
||||
let spawner = Spawner::for_current_executor().await;
|
||||
|
||||
let device = self.interfaces.take().unwrap().ap;
|
||||
let gw_ip_addr_str = "192.168.71.1";
|
||||
let gw_ip_addr = Ipv4Addr::from_str(gw_ip_addr_str).expect("failed to parse gateway ip");
|
||||
|
||||
let config = embassy_net::Config::ipv4_static(StaticConfigV4 {
|
||||
address: Ipv4Cidr::new(gw_ip_addr, 24),
|
||||
gateway: Some(gw_ip_addr),
|
||||
dns_servers: Default::default(),
|
||||
});
|
||||
|
||||
let seed = (self.rng.random() as u64) << 32 | self.rng.random() as u64;
|
||||
|
||||
// Init network stack
|
||||
let (stack, runner) = embassy_net::new(
|
||||
device,
|
||||
config,
|
||||
mk_static!(StackResources<4>, StackResources::<4>::new()),
|
||||
seed,
|
||||
);
|
||||
let stack = mk_static!(Stack, stack);
|
||||
|
||||
spawner
|
||||
.spawn(connection(self.controller.clone(), ssid.to_owned()))
|
||||
.ok();
|
||||
spawner.spawn(net_task(runner)).ok();
|
||||
spawner.spawn(run_dhcp(stack.clone(), gw_ip_addr_str)).ok();
|
||||
|
||||
loop {
|
||||
if stack.is_link_up() {
|
||||
break;
|
||||
pub fn deep_sleep_ms(&mut self, duration_in_ms: u64) -> ! {
|
||||
// Mark the current OTA image as valid if we reached here while in pending verify.
|
||||
if let Ok(cur) = self.ota.current_ota_state() {
|
||||
if cur == OtaImageState::PendingVerify {
|
||||
info!("Marking OTA image as valid");
|
||||
if let Err(err) = self.ota.set_current_ota_state(Valid) {
|
||||
error!("Could not set image to valid: {:?}", err);
|
||||
}
|
||||
}
|
||||
Timer::after(Duration::from_millis(500)).await;
|
||||
} else {
|
||||
info!("No OTA image to mark as valid");
|
||||
}
|
||||
while !stack.is_config_up() {
|
||||
Timer::after(Duration::from_millis(100)).await
|
||||
}
|
||||
println!(
|
||||
"Connect to the AP `${ssid}` and point your browser to http://{gw_ip_addr_str}/"
|
||||
);
|
||||
stack
|
||||
.config_v4()
|
||||
.inspect(|c| println!("ipv4 config: {c:?}"));
|
||||
|
||||
Ok(stack.clone())
|
||||
}
|
||||
|
||||
pub async fn deep_sleep(&mut self, duration_in_ms: u64) -> ! {
|
||||
RtcSleepConfig::deep();
|
||||
|
||||
let cur = self.ota.current_ota_state().unwrap();
|
||||
//we made it till here, so fine
|
||||
if cur == OtaImageState::PendingVerify {
|
||||
self.ota
|
||||
.set_current_ota_state(OtaImageState::Valid)
|
||||
.expect("Could not set image to valid");
|
||||
}
|
||||
//unsafe {
|
||||
// //allow early wakeup by pressing the boot button
|
||||
if duration_in_ms == 0 {
|
||||
software_reset();
|
||||
} else {
|
||||
loop {
|
||||
info!("todo deepsleep")
|
||||
}
|
||||
// //configure gpio 1 to wakeup on low, reused boot button for this
|
||||
// esp_sleep_enable_ext1_wakeup(
|
||||
// 0b10u64,
|
||||
// esp_sleep_ext1_wakeup_mode_t_ESP_EXT1_WAKEUP_ANY_LOW,
|
||||
// );
|
||||
// esp_deep_sleep(duration_in_ms);
|
||||
let timer = TimerWakeupSource::new(core::time::Duration::from_millis(duration_in_ms));
|
||||
let mut wake_pins: [(&mut dyn RtcPinWithResistors, WakeupLevel); 1] =
|
||||
[(&mut self.wake_gpio1, WakeupLevel::Low)];
|
||||
let ext1 = esp_hal::rtc_cntl::sleep::Ext1WakeupSource::new(&mut wake_pins);
|
||||
self.rtc.sleep_deep(&[&timer, &ext1]);
|
||||
}
|
||||
//};
|
||||
}
|
||||
|
||||
pub(crate) async fn wifi(&mut self, network_config: &NetworkConfig) -> FatResult<IpInfo> {
|
||||
let _ssid = network_config.ssid.clone();
|
||||
match &_ssid {
|
||||
Some(ssid) => {
|
||||
if ssid.is_empty() {
|
||||
bail!("Wifi ssid was empty")
|
||||
}
|
||||
}
|
||||
None => {
|
||||
bail!("Wifi ssid was empty")
|
||||
}
|
||||
}
|
||||
let _ssid = _ssid.unwrap();
|
||||
let _password = network_config.password.clone();
|
||||
let _max_wait = network_config.max_wait;
|
||||
bail!("todo")
|
||||
// match password {
|
||||
// Some(pw) => {
|
||||
// //TODO expect error due to invalid pw or similar! //call this during configuration and check if works, revert to config mode if not
|
||||
// self.wifi_driver.set_configuration(&Configuration::Client(
|
||||
// ClientConfiguration {
|
||||
// ssid,
|
||||
// password: pw,
|
||||
// ..Default::default()
|
||||
// },
|
||||
// ))?;
|
||||
// }
|
||||
// None => {
|
||||
// self.wifi_driver.set_configuration(&Configuration::Client(
|
||||
// ClientConfiguration {
|
||||
// ssid,
|
||||
// auth_method: AuthMethod::None,
|
||||
// ..Default::default()
|
||||
// },
|
||||
// ))?;
|
||||
// }
|
||||
// }
|
||||
//
|
||||
// self.wifi_driver.start()?;
|
||||
// self.wifi_driver.connect()?;
|
||||
//
|
||||
// let delay = Delay::new_default();
|
||||
// let mut counter = 0_u32;
|
||||
// while !self.wifi_driver.is_connected()? {
|
||||
// delay.delay_ms(250);
|
||||
// counter += 250;
|
||||
// if counter > max_wait {
|
||||
// //ignore these errors, Wi-Fi will not be used this
|
||||
// self.wifi_driver.disconnect().unwrap_or(());
|
||||
// self.wifi_driver.stop().unwrap_or(());
|
||||
// bail!("Did not manage wifi connection within timeout");
|
||||
// }
|
||||
// }
|
||||
// log::info!("Should be connected now, waiting for link to be up");
|
||||
//
|
||||
// while !self.wifi_driver.is_up()? {
|
||||
// delay.delay_ms(250);
|
||||
// counter += 250;
|
||||
// if counter > max_wait {
|
||||
// //ignore these errors, Wi-Fi will not be used this
|
||||
// self.wifi_driver.disconnect().unwrap_or(());
|
||||
// self.wifi_driver.stop().unwrap_or(());
|
||||
// bail!("Did not manage wifi connection within timeout");
|
||||
// }
|
||||
// }
|
||||
// //update freertos registers ;)
|
||||
// let address = self.wifi_driver.sta_netif().get_ip_info()?;
|
||||
// log(LogMessage::WifiInfo, 0, 0, "", &format!("{address:?}"));
|
||||
// anyhow::Ok(address)
|
||||
}
|
||||
pub(crate) async fn load_config(&mut self) -> FatResult<PlantControllerConfig> {
|
||||
let cfg = PathBuf::try_from(CONFIG_FILE).unwrap();
|
||||
let data = self.fs.lock().await.read::<4096>(&cfg)?;
|
||||
@@ -495,326 +417,39 @@ impl Esp<'_> {
|
||||
} else {
|
||||
RESTART_TO_CONF = 0;
|
||||
}
|
||||
LAST_CORROSION_PROTECTION_CHECK_DAY = -1;
|
||||
};
|
||||
} else {
|
||||
unsafe {
|
||||
if to_config_mode {
|
||||
RESTART_TO_CONF = 1;
|
||||
}
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
LogMessage::RestartToConfig,
|
||||
RESTART_TO_CONF as u32,
|
||||
0,
|
||||
"",
|
||||
"",
|
||||
)
|
||||
.await;
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
LogMessage::LowVoltage,
|
||||
LOW_VOLTAGE_DETECTED as u32,
|
||||
0,
|
||||
"",
|
||||
"",
|
||||
)
|
||||
.await;
|
||||
for i in 0..PLANT_COUNT {
|
||||
log::info!(
|
||||
"LAST_WATERING_TIMESTAMP[{}] = UTC {}",
|
||||
i,
|
||||
LAST_WATERING_TIMESTAMP[i]
|
||||
);
|
||||
log(
|
||||
LogMessage::RestartToConfig,
|
||||
RESTART_TO_CONF as u32,
|
||||
0,
|
||||
"",
|
||||
"",
|
||||
);
|
||||
log(
|
||||
LogMessage::LowVoltage,
|
||||
LOW_VOLTAGE_DETECTED as u32,
|
||||
0,
|
||||
"",
|
||||
"",
|
||||
);
|
||||
// is executed before main, no other code will alter these values during printing
|
||||
#[allow(static_mut_refs)]
|
||||
for (i, time) in LAST_WATERING_TIMESTAMP.iter().enumerate() {
|
||||
info!("LAST_WATERING_TIMESTAMP[{i}] = UTC {time}");
|
||||
}
|
||||
for i in 0..PLANT_COUNT {
|
||||
log::info!(
|
||||
"CONSECUTIVE_WATERING_PLANT[{}] = {}",
|
||||
i,
|
||||
CONSECUTIVE_WATERING_PLANT[i]
|
||||
);
|
||||
// is executed before main, no other code will alter these values during printing
|
||||
#[allow(static_mut_refs)]
|
||||
for (i, item) in CONSECUTIVE_WATERING_PLANT.iter().enumerate() {
|
||||
info!("CONSECUTIVE_WATERING_PLANT[{i}] = {item}");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn mqtt(&mut self, network_config: &NetworkConfig) -> FatResult<()> {
|
||||
let base_topic = network_config
|
||||
.base_topic
|
||||
.as_ref()
|
||||
.context("missing base topic")?;
|
||||
if base_topic.is_empty() {
|
||||
bail!("Mqtt base_topic was empty")
|
||||
}
|
||||
let _base_topic_copy = base_topic.clone();
|
||||
let mqtt_url = network_config
|
||||
.mqtt_url
|
||||
.as_ref()
|
||||
.context("missing mqtt url")?;
|
||||
if mqtt_url.is_empty() {
|
||||
bail!("Mqtt url was empty")
|
||||
}
|
||||
|
||||
bail!("todo");
|
||||
//
|
||||
// let last_will_topic = format!("{}/state", base_topic);
|
||||
// let mqtt_client_config = MqttClientConfiguration {
|
||||
// lwt: Some(LwtConfiguration {
|
||||
// topic: &last_will_topic,
|
||||
// payload: "lost".as_bytes(),
|
||||
// qos: AtLeastOnce,
|
||||
// retain: true,
|
||||
// }),
|
||||
// client_id: Some("plantctrl"),
|
||||
// keep_alive_interval: Some(Duration::from_secs(60 * 60 * 2)),
|
||||
// username: network_config.mqtt_user.as_ref().map(|v| &**v),
|
||||
// password: network_config.mqtt_password.as_ref().map(|v| &**v),
|
||||
// //room for improvement
|
||||
// ..Default::default()
|
||||
// };
|
||||
//
|
||||
// let mqtt_connected_event_received = Arc::new(AtomicBool::new(false));
|
||||
// let mqtt_connected_event_ok = Arc::new(AtomicBool::new(false));
|
||||
//
|
||||
// let round_trip_ok = Arc::new(AtomicBool::new(false));
|
||||
// let round_trip_topic = format!("{}/internal/roundtrip", base_topic);
|
||||
// let stay_alive_topic = format!("{}/stay_alive", base_topic);
|
||||
// log(LogMessage::StayAlive, 0, 0, "", &stay_alive_topic);
|
||||
//
|
||||
// let mqtt_connected_event_received_copy = mqtt_connected_event_received.clone();
|
||||
// let mqtt_connected_event_ok_copy = mqtt_connected_event_ok.clone();
|
||||
// let stay_alive_topic_copy = stay_alive_topic.clone();
|
||||
// let round_trip_topic_copy = round_trip_topic.clone();
|
||||
// let round_trip_ok_copy = round_trip_ok.clone();
|
||||
// let client_id = mqtt_client_config.client_id.unwrap_or("not set");
|
||||
// log(LogMessage::MqttInfo, 0, 0, client_id, mqtt_url);
|
||||
// let mut client = EspMqttClient::new_cb(mqtt_url, &mqtt_client_config, move |event| {
|
||||
// let payload = event.payload();
|
||||
// match payload {
|
||||
// embedded_svc::mqtt::client::EventPayload::Received {
|
||||
// id: _,
|
||||
// topic,
|
||||
// data,
|
||||
// details: _,
|
||||
// } => {
|
||||
// let data = String::from_utf8_lossy(data);
|
||||
// if let Some(topic) = topic {
|
||||
// //todo use enums
|
||||
// if topic.eq(round_trip_topic_copy.as_str()) {
|
||||
// round_trip_ok_copy.store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// } else if topic.eq(stay_alive_topic_copy.as_str()) {
|
||||
// let value =
|
||||
// data.eq_ignore_ascii_case("true") || data.eq_ignore_ascii_case("1");
|
||||
// log(LogMessage::MqttStayAliveRec, 0, 0, &data, "");
|
||||
// STAY_ALIVE.store(value, std::sync::atomic::Ordering::Relaxed);
|
||||
// } else {
|
||||
// log(LogMessage::UnknownTopic, 0, 0, "", topic);
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Connected(_) => {
|
||||
// mqtt_connected_event_received_copy
|
||||
// .store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// mqtt_connected_event_ok_copy.store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// log::info!("Mqtt connected");
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Disconnected => {
|
||||
// mqtt_connected_event_received_copy
|
||||
// .store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed);
|
||||
// log::info!("Mqtt disconnected");
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Error(esp_error) => {
|
||||
// log::info!("EspMqttError reported {:?}", esp_error);
|
||||
// mqtt_connected_event_received_copy
|
||||
// .store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed);
|
||||
// log::info!("Mqtt error");
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::BeforeConnect => {
|
||||
// log::info!("Mqtt before connect")
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Subscribed(_) => {
|
||||
// log::info!("Mqtt subscribed")
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Unsubscribed(_) => {
|
||||
// log::info!("Mqtt unsubscribed")
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Published(_) => {
|
||||
// log::info!("Mqtt published")
|
||||
// }
|
||||
// esp_idf_svc::mqtt::client::EventPayload::Deleted(_) => {
|
||||
// log::info!("Mqtt deleted")
|
||||
// }
|
||||
// }
|
||||
// })?;
|
||||
//
|
||||
// let mut wait_for_connections_event = 0;
|
||||
// while wait_for_connections_event < 100 {
|
||||
// wait_for_connections_event += 1;
|
||||
// match mqtt_connected_event_received.load(std::sync::atomic::Ordering::Relaxed) {
|
||||
// true => {
|
||||
// log::info!("Mqtt connection callback received, progressing");
|
||||
// match mqtt_connected_event_ok.load(std::sync::atomic::Ordering::Relaxed) {
|
||||
// true => {
|
||||
// log::info!(
|
||||
// "Mqtt did callback as connected, testing with roundtrip now"
|
||||
// );
|
||||
// //subscribe to roundtrip
|
||||
// client.subscribe(round_trip_topic.as_str(), ExactlyOnce)?;
|
||||
// client.subscribe(stay_alive_topic.as_str(), ExactlyOnce)?;
|
||||
// //publish to roundtrip
|
||||
// client.publish(
|
||||
// round_trip_topic.as_str(),
|
||||
// ExactlyOnce,
|
||||
// false,
|
||||
// "online_test".as_bytes(),
|
||||
// )?;
|
||||
//
|
||||
// let mut wait_for_roundtrip = 0;
|
||||
// while wait_for_roundtrip < 100 {
|
||||
// wait_for_roundtrip += 1;
|
||||
// match round_trip_ok.load(std::sync::atomic::Ordering::Relaxed) {
|
||||
// true => {
|
||||
// log::info!("Round trip registered, proceeding");
|
||||
// self.mqtt_client = Some(MqttClient {
|
||||
// mqtt_client: client,
|
||||
// base_topic: base_topic_copy,
|
||||
// });
|
||||
// return anyhow::Ok(());
|
||||
// }
|
||||
// false => {
|
||||
// unsafe { vTaskDelay(10) };
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
// bail!("Mqtt did not complete roundtrip in time");
|
||||
// }
|
||||
// false => {
|
||||
// bail!("Mqtt did respond but with failure")
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
// false => {
|
||||
// unsafe { vTaskDelay(10) };
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
// bail!("Mqtt did not fire connection callback in time");
|
||||
}
|
||||
pub(crate) async fn mqtt_publish(&mut self, _subtopic: &str, _message: &[u8]) -> FatResult<()> {
|
||||
bail!("todo");
|
||||
//
|
||||
// if self.mqtt_client.is_none() {
|
||||
// return anyhow::Ok(());
|
||||
// }
|
||||
// if !subtopic.starts_with("/") {
|
||||
// log::info!("Subtopic without / at start {}", subtopic);
|
||||
// bail!("Subtopic without / at start {}", subtopic);
|
||||
// }
|
||||
// if subtopic.len() > 192 {
|
||||
// log::info!("Subtopic exceeds 192 chars {}", subtopic);
|
||||
// bail!("Subtopic exceeds 192 chars {}", subtopic);
|
||||
// }
|
||||
// let client = self.mqtt_client.as_mut().unwrap();
|
||||
// let mut full_topic: heapless::String<256> = heapless::String::new();
|
||||
// if full_topic.push_str(client.base_topic.as_str()).is_err() {
|
||||
// log::info!("Some error assembling full_topic 1");
|
||||
// bail!("Some error assembling full_topic 1")
|
||||
// };
|
||||
// if full_topic.push_str(subtopic).is_err() {
|
||||
// log::info!("Some error assembling full_topic 2");
|
||||
// bail!("Some error assembling full_topic 2")
|
||||
// };
|
||||
// let publish = client
|
||||
// .mqtt_client
|
||||
// .publish(&full_topic, ExactlyOnce, true, message);
|
||||
// Timer::after_millis(10).await;
|
||||
// match publish {
|
||||
// OkStd(message_id) => {
|
||||
// log::info!(
|
||||
// "Published mqtt topic {} with message {:#?} msgid is {:?}",
|
||||
// full_topic,
|
||||
// String::from_utf8_lossy(message),
|
||||
// message_id
|
||||
// );
|
||||
// anyhow::Ok(())
|
||||
// }
|
||||
// Err(err) => {
|
||||
// log::info!(
|
||||
// "Error during mqtt send on topic {} with message {:#?} error is {:?}",
|
||||
// full_topic,
|
||||
// String::from_utf8_lossy(message),
|
||||
// err
|
||||
// );
|
||||
// Err(err)?
|
||||
// }
|
||||
// }
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn run_dhcp(stack: Stack<'static>, gw_ip_addr: &'static str) {
|
||||
use core::net::{Ipv4Addr, SocketAddrV4};
|
||||
|
||||
use edge_dhcp::{
|
||||
io::{self, DEFAULT_SERVER_PORT},
|
||||
server::{Server, ServerOptions},
|
||||
};
|
||||
use edge_nal::UdpBind;
|
||||
use edge_nal_embassy::{Udp, UdpBuffers};
|
||||
|
||||
let ip = Ipv4Addr::from_str(gw_ip_addr).expect("dhcp task failed to parse gw ip");
|
||||
|
||||
let mut buf = [0u8; 1500];
|
||||
|
||||
let mut gw_buf = [Ipv4Addr::UNSPECIFIED];
|
||||
|
||||
let buffers = UdpBuffers::<3, 1024, 1024, 10>::new();
|
||||
let unbound_socket = Udp::new(stack, &buffers);
|
||||
let mut bound_socket = unbound_socket
|
||||
.bind(core::net::SocketAddr::V4(SocketAddrV4::new(
|
||||
Ipv4Addr::UNSPECIFIED,
|
||||
DEFAULT_SERVER_PORT,
|
||||
)))
|
||||
.await
|
||||
.unwrap();
|
||||
|
||||
loop {
|
||||
_ = io::server::run(
|
||||
&mut Server::<_, 64>::new_with_et(ip),
|
||||
&ServerOptions::new(ip, Some(&mut gw_buf)),
|
||||
&mut bound_socket,
|
||||
&mut buf,
|
||||
)
|
||||
.await
|
||||
.inspect_err(|e| log::warn!("DHCP server error: {e:?}"));
|
||||
Timer::after(Duration::from_millis(500)).await;
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn connection(
|
||||
controller: Arc<Mutex<CriticalSectionRawMutex, WifiController<'static>>>,
|
||||
ssid: String,
|
||||
) {
|
||||
let client_config = Configuration::AccessPoint(AccessPointConfiguration {
|
||||
ssid: ssid.clone(),
|
||||
..Default::default()
|
||||
});
|
||||
controller
|
||||
.lock()
|
||||
.await
|
||||
.set_configuration(&client_config)
|
||||
.unwrap();
|
||||
controller.lock().await.start_async().await.unwrap();
|
||||
println!("Wifi started!");
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn net_task(mut runner: Runner<'static, WifiDevice<'static>>) {
|
||||
runner.run().await
|
||||
}
|
||||
|
||||
@@ -1,16 +1,16 @@
|
||||
use crate::alloc::boxed::Box;
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::esp::Esp;
|
||||
use crate::hal::rtc::{BackupHeader, RTCModuleInteraction};
|
||||
use crate::hal::water::TankSensor;
|
||||
use crate::hal::{BoardInteraction, FreePeripherals, Sensor};
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::{
|
||||
bail,
|
||||
config::PlantControllerConfig,
|
||||
hal::battery::{BatteryInteraction, NoBatteryMonitor},
|
||||
};
|
||||
use async_trait::async_trait;
|
||||
use chrono::{DateTime, Utc};
|
||||
use chrono::{DateTime, FixedOffset, Utc};
|
||||
use esp_hal::gpio::{Level, Output, OutputConfig};
|
||||
use measurements::{Current, Voltage};
|
||||
|
||||
@@ -90,12 +90,22 @@ impl<'a> BoardInteraction<'a> for Initial<'a> {
|
||||
&mut self.rtc
|
||||
}
|
||||
|
||||
fn set_charge_indicator(&mut self, _charging: bool) -> Result<(), FatError> {
|
||||
async fn get_time(&mut self) -> DateTime<Utc> {
|
||||
self.esp.get_time()
|
||||
}
|
||||
|
||||
async fn set_time(&mut self, time: &DateTime<FixedOffset>) -> FatResult<()> {
|
||||
self.rtc.set_rtc_time(&time.to_utc()).await?;
|
||||
self.esp.set_time(time.to_utc());
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn set_charge_indicator(&mut self, _charging: bool) -> Result<(), FatError> {
|
||||
bail!("Please configure board revision")
|
||||
}
|
||||
|
||||
async fn deep_sleep(&mut self, duration_in_ms: u64) -> ! {
|
||||
self.esp.deep_sleep(duration_in_ms).await;
|
||||
async fn deep_sleep_ms(&mut self, duration_in_ms: u64) -> ! {
|
||||
self.esp.deep_sleep_ms(duration_in_ms);
|
||||
}
|
||||
fn is_day(&self) -> bool {
|
||||
false
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
use embedded_storage::{ReadStorage, Storage};
|
||||
use crate::hal::shared_flash::MutexFlashStorage;
|
||||
use embedded_storage::nor_flash::{check_erase, NorFlash, ReadNorFlash};
|
||||
use esp_bootloader_esp_idf::partitions::FlashRegion;
|
||||
use esp_storage::FlashStorage;
|
||||
use littlefs2::consts::U512 as lfsCache;
|
||||
use littlefs2::consts::U4096 as lfsCache;
|
||||
use littlefs2::consts::U512 as lfsLookahead;
|
||||
use littlefs2::driver::Storage as lfs2Storage;
|
||||
use littlefs2::io::Error as lfs2Error;
|
||||
@@ -9,26 +9,32 @@ use littlefs2::io::Result as lfs2Result;
|
||||
use log::error;
|
||||
|
||||
pub struct LittleFs2Filesystem {
|
||||
pub(crate) storage: &'static mut FlashRegion<'static, FlashStorage>,
|
||||
pub(crate) storage: &'static mut FlashRegion<'static, MutexFlashStorage>,
|
||||
}
|
||||
|
||||
impl lfs2Storage for LittleFs2Filesystem {
|
||||
const READ_SIZE: usize = 256;
|
||||
const WRITE_SIZE: usize = 512;
|
||||
const BLOCK_SIZE: usize = 512; //usually optimal for flash access
|
||||
const BLOCK_COUNT: usize = 8 * 1024 * 1024 / 512; //8mb in 32kb blocks
|
||||
const READ_SIZE: usize = 4096;
|
||||
const WRITE_SIZE: usize = 4096;
|
||||
const BLOCK_SIZE: usize = 4096; //usually optimal for flash access
|
||||
const BLOCK_COUNT: usize = 8 * 1000 * 1000 / 4096; //8Mb in 4k blocks + a little space for stupid calculation errors
|
||||
const BLOCK_CYCLES: isize = 100;
|
||||
type CACHE_SIZE = lfsCache;
|
||||
type LOOKAHEAD_SIZE = lfsLookahead;
|
||||
|
||||
fn read(&mut self, off: usize, buf: &mut [u8]) -> lfs2Result<usize> {
|
||||
let read_size: usize = Self::READ_SIZE;
|
||||
assert_eq!(off % read_size, 0);
|
||||
assert_eq!(buf.len() % read_size, 0);
|
||||
if off % read_size != 0 {
|
||||
error!("Littlefs2Filesystem read error: offset not aligned to read size offset: {off} read_size: {read_size}");
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
if buf.len() % read_size != 0 {
|
||||
error!("Littlefs2Filesystem read error: length not aligned to read size length: {} read_size: {}", buf.len(), read_size);
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
match self.storage.read(off as u32, buf) {
|
||||
Ok(..) => Ok(buf.len()),
|
||||
Err(err) => {
|
||||
error!("Littlefs2Filesystem read error: {:?}", err);
|
||||
error!("Littlefs2Filesystem read error: {err:?}");
|
||||
Err(lfs2Error::IO)
|
||||
}
|
||||
}
|
||||
@@ -36,12 +42,18 @@ impl lfs2Storage for LittleFs2Filesystem {
|
||||
|
||||
fn write(&mut self, off: usize, data: &[u8]) -> lfs2Result<usize> {
|
||||
let write_size: usize = Self::WRITE_SIZE;
|
||||
assert_eq!(off % write_size, 0);
|
||||
assert_eq!(data.len() % write_size, 0);
|
||||
if off % write_size != 0 {
|
||||
error!("Littlefs2Filesystem write error: offset not aligned to write size offset: {off} write_size: {write_size}");
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
if data.len() % write_size != 0 {
|
||||
error!("Littlefs2Filesystem write error: length not aligned to write size length: {} write_size: {}", data.len(), write_size);
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
match self.storage.write(off as u32, data) {
|
||||
Ok(..) => Ok(data.len()),
|
||||
Err(err) => {
|
||||
error!("Littlefs2Filesystem write error: {:?}", err);
|
||||
error!("Littlefs2Filesystem write error: {err:?}");
|
||||
Err(lfs2Error::IO)
|
||||
}
|
||||
}
|
||||
@@ -49,15 +61,28 @@ impl lfs2Storage for LittleFs2Filesystem {
|
||||
|
||||
fn erase(&mut self, off: usize, len: usize) -> lfs2Result<usize> {
|
||||
let block_size: usize = Self::BLOCK_SIZE;
|
||||
debug_assert!(off % block_size == 0);
|
||||
debug_assert!(len % block_size == 0);
|
||||
//match self.storage.erase(off as u32, len as u32) {
|
||||
//anyhow::Result::Ok(..) => lfs2Result::Ok(len),
|
||||
//Err(err) => {
|
||||
//error!("Littlefs2Filesystem erase error: {:?}", err);
|
||||
//Err(lfs2Error::IO)
|
||||
// }
|
||||
//}
|
||||
lfs2Result::Ok(len)
|
||||
if off % block_size != 0 {
|
||||
error!("Littlefs2Filesystem erase error: offset not aligned to block size offset: {off} block_size: {block_size}");
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
if len % block_size != 0 {
|
||||
error!("Littlefs2Filesystem erase error: length not aligned to block size length: {len} block_size: {block_size}");
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
|
||||
match check_erase(self.storage, off as u32, (off + len) as u32) {
|
||||
Ok(_) => {}
|
||||
Err(err) => {
|
||||
error!("Littlefs2Filesystem check erase error: {err:?}");
|
||||
return Err(lfs2Error::IO);
|
||||
}
|
||||
}
|
||||
match self.storage.erase(off as u32, (off + len) as u32) {
|
||||
Ok(..) => Ok(len),
|
||||
Err(err) => {
|
||||
error!("Littlefs2Filesystem erase error: {err:?}");
|
||||
Err(lfs2Error::IO)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -3,17 +3,20 @@ pub mod esp;
|
||||
mod initial_hal;
|
||||
mod little_fs2storage_adapter;
|
||||
pub(crate) mod rtc;
|
||||
mod shared_flash;
|
||||
mod v3_hal;
|
||||
mod v3_shift_register;
|
||||
mod v4_hal;
|
||||
mod v4_sensor;
|
||||
mod water;
|
||||
|
||||
use crate::alloc::string::ToString;
|
||||
use crate::hal::rtc::{DS3231Module, RTCModuleInteraction};
|
||||
use esp_hal::interrupt::software::SoftwareInterruptControl;
|
||||
use esp_hal::peripherals::Peripherals;
|
||||
use esp_hal::peripherals::ADC1;
|
||||
use esp_hal::peripherals::APB_SARADC;
|
||||
use esp_hal::peripherals::GPIO0;
|
||||
use esp_hal::peripherals::GPIO1;
|
||||
use esp_hal::peripherals::GPIO10;
|
||||
use esp_hal::peripherals::GPIO11;
|
||||
use esp_hal::peripherals::GPIO12;
|
||||
@@ -42,6 +45,7 @@ use esp_hal::peripherals::GPIO7;
|
||||
use esp_hal::peripherals::GPIO8;
|
||||
use esp_hal::peripherals::PCNT;
|
||||
use esp_hal::peripherals::TWAI0;
|
||||
use portable_atomic::AtomicBool;
|
||||
|
||||
use crate::{
|
||||
bail,
|
||||
@@ -68,28 +72,31 @@ use eeprom24x::page_size::B32;
|
||||
use eeprom24x::unique_serial::No;
|
||||
use eeprom24x::{Eeprom24x, SlaveAddr, Storage};
|
||||
use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_sync::blocking_mutex::CriticalSectionMutex;
|
||||
//use battery::BQ34Z100G1;
|
||||
//use bq34z100::Bq34z100g1Driver;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::blocking_mutex::CriticalSectionMutex;
|
||||
use embedded_storage::nor_flash::RmwNorFlashStorage;
|
||||
use embedded_storage::ReadStorage;
|
||||
use esp_bootloader_esp_idf::partitions::{
|
||||
AppPartitionSubType, DataPartitionSubType, FlashRegion, PartitionEntry,
|
||||
AppPartitionSubType, DataPartitionSubType, FlashRegion, PartitionEntry, PartitionTable,
|
||||
PartitionType,
|
||||
};
|
||||
use esp_hal::clock::CpuClock;
|
||||
use esp_hal::gpio::{Input, InputConfig, Pull};
|
||||
use esp_hal::uart::{Config as UartConfig, Uart};
|
||||
use esp_storage::FlashStorage;
|
||||
use lib_bms_protocol::{BmsReadable, ProtocolVersion};
|
||||
use measurements::{Current, Voltage};
|
||||
|
||||
use crate::fat_error::{ContextExt, FatError, FatResult};
|
||||
use crate::hal::battery::{print_battery_bq34z100, BQ34Z100G1};
|
||||
use crate::hal::little_fs2storage_adapter::LittleFs2Filesystem;
|
||||
use crate::hal::water::TankSensor;
|
||||
use crate::log::LOG_ACCESS;
|
||||
use crate::fat_error::FatError;
|
||||
use crate::log::log;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use embassy_sync::once_lock::OnceLock;
|
||||
use esp_alloc as _;
|
||||
use esp_backtrace as _;
|
||||
use esp_bootloader_esp_idf::ota::Slot;
|
||||
use esp_bootloader_esp_idf::ota::{OtaImageState, Ota};
|
||||
use esp_hal::delay::Delay;
|
||||
use esp_hal::i2c::master::{BusTimeout, Config, I2c};
|
||||
use esp_hal::pcnt::unit::Unit;
|
||||
@@ -98,19 +105,25 @@ use esp_hal::rng::Rng;
|
||||
use esp_hal::rtc_cntl::{Rtc, SocResetReason};
|
||||
use esp_hal::system::reset_reason;
|
||||
use esp_hal::time::Rate;
|
||||
use esp_hal::timer::timg::TimerGroup;
|
||||
use esp_hal::timer::timg::{TimerGroup, Wdt};
|
||||
use esp_hal::Blocking;
|
||||
use esp_storage::FlashStorage;
|
||||
use esp_wifi::{init, EspWifiController};
|
||||
use littlefs2::fs::{Allocation, Filesystem as lfs2Filesystem};
|
||||
use littlefs2::object_safe::DynStorage;
|
||||
use log::{info, warn};
|
||||
use log::{error, info, warn};
|
||||
use shared_flash::MutexFlashStorage;
|
||||
|
||||
pub static TIME_ACCESS: OnceLock<Rtc> = OnceLock::new();
|
||||
pub static PROGRESS_ACTIVE: AtomicBool = AtomicBool::new(false);
|
||||
|
||||
//Only support for 8 right now!
|
||||
pub const PLANT_COUNT: usize = 8;
|
||||
|
||||
pub static WATCHDOG: OnceLock<
|
||||
embassy_sync::blocking_mutex::Mutex<
|
||||
CriticalSectionRawMutex,
|
||||
RefCell<Wdt<esp_hal::peripherals::TIMG0>>,
|
||||
>,
|
||||
> = OnceLock::new();
|
||||
|
||||
const TANK_MULTI_SAMPLE: usize = 11;
|
||||
pub static I2C_DRIVER: OnceLock<
|
||||
embassy_sync::blocking_mutex::Mutex<CriticalSectionRawMutex, RefCell<I2c<Blocking>>>,
|
||||
@@ -128,6 +141,70 @@ pub struct HAL<'a> {
|
||||
pub board_hal: Box<dyn BoardInteraction<'a> + Send>,
|
||||
}
|
||||
|
||||
fn ota_state(
|
||||
slot: AppPartitionSubType,
|
||||
ota_data: &mut FlashRegion<RmwNorFlashStorage<&mut MutexFlashStorage>>,
|
||||
) -> OtaImageState {
|
||||
// Read and log OTA states for both slots before constructing Ota
|
||||
// Each OTA select entry is 32 bytes: [seq:4][label:20][state:4][crc:4]
|
||||
// Offsets within the OTA data partition: slot0 @ 0x0000, slot1 @ 0x1000
|
||||
let mut slot_buf = [0u8; 32];
|
||||
if slot == AppPartitionSubType::Ota0 {
|
||||
let _ = ReadStorage::read(ota_data, 0x0000, &mut slot_buf);
|
||||
} else {
|
||||
let _ = ReadStorage::read(ota_data, 0x1000, &mut slot_buf);
|
||||
}
|
||||
let raw_state = u32::from_le_bytes(slot_buf[24..28].try_into().unwrap_or([0xff; 4]));
|
||||
|
||||
OtaImageState::try_from(raw_state).unwrap_or(OtaImageState::Undefined)
|
||||
}
|
||||
fn get_current_slot(
|
||||
pt: &PartitionTable,
|
||||
ota: &mut Ota<RmwNorFlashStorage<&mut MutexFlashStorage>>,
|
||||
) -> Result<AppPartitionSubType, FatError> {
|
||||
let booted = pt.booted_partition()?.ok_or(FatError::OTAError)?;
|
||||
let booted_type = booted.partition_type();
|
||||
let booted_ota_type = match booted_type {
|
||||
PartitionType::App(subtype) => subtype,
|
||||
_ => {
|
||||
bail!("Booted partition is not an app partition");
|
||||
}
|
||||
};
|
||||
|
||||
let expected_partition = ota.current_app_partition()?;
|
||||
if expected_partition == booted_ota_type {
|
||||
info!("Booted partition matches expected partition");
|
||||
} else {
|
||||
info!("Booted partition does not match expected partition, fixing ota entry");
|
||||
ota.set_current_app_partition(booted_ota_type)?;
|
||||
}
|
||||
|
||||
let fixed = ota.current_app_partition()?;
|
||||
let state = ota.current_ota_state();
|
||||
info!("Expected partition: {expected_partition:?}, current partition: {booted_ota_type:?}, state: {state:?}");
|
||||
|
||||
if fixed != booted_ota_type {
|
||||
bail!(
|
||||
"Could not fix ota entry, booted partition is still not correct: {:?} != {:?}",
|
||||
booted_ota_type,
|
||||
fixed
|
||||
);
|
||||
}
|
||||
|
||||
Ok(booted_ota_type)
|
||||
}
|
||||
|
||||
pub fn next_partition(current: AppPartitionSubType) -> FatResult<AppPartitionSubType> {
|
||||
let next = match current {
|
||||
AppPartitionSubType::Ota0 => AppPartitionSubType::Ota1,
|
||||
AppPartitionSubType::Ota1 => AppPartitionSubType::Ota0,
|
||||
_ => {
|
||||
bail!("Current slot is not ota0 or ota1");
|
||||
}
|
||||
};
|
||||
Ok(next)
|
||||
}
|
||||
|
||||
#[async_trait]
|
||||
pub trait BoardInteraction<'a> {
|
||||
fn get_tank_sensor(&mut self) -> Result<&mut TankSensor<'a>, FatError>;
|
||||
@@ -135,8 +212,10 @@ pub trait BoardInteraction<'a> {
|
||||
fn get_config(&mut self) -> &PlantControllerConfig;
|
||||
fn get_battery_monitor(&mut self) -> &mut Box<dyn BatteryInteraction + Send>;
|
||||
fn get_rtc_module(&mut self) -> &mut Box<dyn RTCModuleInteraction + Send>;
|
||||
fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError>;
|
||||
async fn deep_sleep(&mut self, duration_in_ms: u64) -> !;
|
||||
async fn get_time(&mut self) -> DateTime<Utc>;
|
||||
async fn set_time(&mut self, time: &DateTime<FixedOffset>) -> FatResult<()>;
|
||||
async fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError>;
|
||||
async fn deep_sleep_ms(&mut self, duration_in_ms: u64) -> !;
|
||||
|
||||
fn is_day(&self) -> bool;
|
||||
//should be multsampled
|
||||
@@ -175,7 +254,6 @@ pub trait BoardInteraction<'a> {
|
||||
#[allow(dead_code)]
|
||||
pub struct FreePeripherals<'a> {
|
||||
pub gpio0: GPIO0<'a>,
|
||||
pub gpio1: GPIO1<'a>,
|
||||
pub gpio2: GPIO2<'a>,
|
||||
pub gpio3: GPIO3<'a>,
|
||||
pub gpio4: GPIO4<'a>,
|
||||
@@ -197,77 +275,46 @@ pub struct FreePeripherals<'a> {
|
||||
pub gpio21: GPIO21<'a>,
|
||||
pub gpio22: GPIO22<'a>,
|
||||
pub gpio23: GPIO23<'a>,
|
||||
pub gpio24: GPIO24<'a>,
|
||||
pub gpio25: GPIO25<'a>,
|
||||
pub gpio26: GPIO26<'a>,
|
||||
pub gpio27: GPIO27<'a>,
|
||||
pub gpio28: GPIO28<'a>,
|
||||
pub gpio29: GPIO29<'a>,
|
||||
pub gpio30: GPIO30<'a>,
|
||||
pub twai: TWAI0<'a>,
|
||||
pub pcnt0: Unit<'a, 0>,
|
||||
pub pcnt1: Unit<'a, 1>,
|
||||
pub adc1: ADC1<'a>,
|
||||
}
|
||||
|
||||
macro_rules! mk_static {
|
||||
($t:ty,$val:expr) => {{
|
||||
static STATIC_CELL: static_cell::StaticCell<$t> = static_cell::StaticCell::new();
|
||||
#[deny(unused_attributes)]
|
||||
let x = STATIC_CELL.uninit().write(($val));
|
||||
x
|
||||
}};
|
||||
}
|
||||
|
||||
const GW_IP_ADDR_ENV: Option<&'static str> = option_env!("GATEWAY_IP");
|
||||
use crate::util::mk_static;
|
||||
|
||||
impl PlantHal {
|
||||
pub async fn create(
|
||||
spawner: Spawner,
|
||||
) -> Result<Mutex<CriticalSectionRawMutex, HAL<'static>>, FatError> {
|
||||
pub async fn create() -> Result<Mutex<CriticalSectionRawMutex, HAL<'static>>, FatError> {
|
||||
let config = esp_hal::Config::default().with_cpu_clock(CpuClock::max());
|
||||
let peripherals: Peripherals = esp_hal::init(config);
|
||||
|
||||
esp_alloc::heap_allocator!(size: 64 * 1024);
|
||||
esp_alloc::heap_allocator!(#[link_section = ".dram2_uninit"] size: 64000);
|
||||
|
||||
let rtc: Rtc = Rtc::new(peripherals.LPWR);
|
||||
TIME_ACCESS.init(rtc).map_err(|_| FatError::String {
|
||||
error: "Init error rct".to_string(),
|
||||
})?;
|
||||
let mut rtc_peripheral: Rtc = Rtc::new(peripherals.LPWR);
|
||||
rtc_peripheral.rwdt.disable();
|
||||
|
||||
let systimer = SystemTimer::new(peripherals.SYSTIMER);
|
||||
let timg0 = TimerGroup::new(peripherals.TIMG0);
|
||||
let sw_int = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);
|
||||
esp_rtos::start(timg0.timer0, sw_int.software_interrupt0);
|
||||
|
||||
let boot_button = Input::new(
|
||||
peripherals.GPIO9,
|
||||
InputConfig::default().with_pull(Pull::None),
|
||||
);
|
||||
|
||||
let rng = Rng::new(peripherals.RNG);
|
||||
let timg0 = TimerGroup::new(peripherals.TIMG0);
|
||||
let esp_wifi_ctrl = &*mk_static!(
|
||||
EspWifiController<'static>,
|
||||
init(timg0.timer0, rng.clone()).expect("Could not init wifi controller")
|
||||
);
|
||||
// Reserve GPIO1 for deep sleep wake (configured just before entering sleep)
|
||||
let wake_gpio1 = peripherals.GPIO1;
|
||||
|
||||
let (controller, interfaces) =
|
||||
esp_wifi::wifi::new(&esp_wifi_ctrl, peripherals.WIFI).expect("Could not init wifi");
|
||||
|
||||
use esp_hal::timer::systimer::SystemTimer;
|
||||
esp_hal_embassy::init(systimer.alarm0);
|
||||
|
||||
//let mut adc1 = Adc::new(peripherals.ADC1, adc1_config);
|
||||
//
|
||||
let rng = Rng::new();
|
||||
let (controller, interfaces) = esp_radio::wifi::new(peripherals.WIFI, Default::default())
|
||||
.expect("Could not init wifi");
|
||||
|
||||
let pcnt_module = Pcnt::new(peripherals.PCNT);
|
||||
|
||||
let free_pins = FreePeripherals {
|
||||
// can: peripherals.can,
|
||||
// adc1: peripherals.adc1,
|
||||
// pcnt0: peripherals.pcnt0,
|
||||
// pcnt1: peripherals.pcnt1,
|
||||
gpio0: peripherals.GPIO0,
|
||||
gpio1: peripherals.GPIO1,
|
||||
gpio2: peripherals.GPIO2,
|
||||
gpio3: peripherals.GPIO3,
|
||||
gpio4: peripherals.GPIO4,
|
||||
@@ -287,13 +334,7 @@ impl PlantHal {
|
||||
gpio21: peripherals.GPIO21,
|
||||
gpio22: peripherals.GPIO22,
|
||||
gpio23: peripherals.GPIO23,
|
||||
gpio24: peripherals.GPIO24,
|
||||
gpio25: peripherals.GPIO25,
|
||||
gpio26: peripherals.GPIO26,
|
||||
gpio27: peripherals.GPIO27,
|
||||
gpio28: peripherals.GPIO28,
|
||||
gpio29: peripherals.GPIO29,
|
||||
gpio30: peripherals.GPIO30,
|
||||
twai: peripherals.TWAI0,
|
||||
pcnt0: pcnt_module.unit0,
|
||||
pcnt1: pcnt_module.unit1,
|
||||
@@ -304,14 +345,19 @@ impl PlantHal {
|
||||
[u8; esp_bootloader_esp_idf::partitions::PARTITION_TABLE_MAX_LEN],
|
||||
[0u8; esp_bootloader_esp_idf::partitions::PARTITION_TABLE_MAX_LEN]
|
||||
);
|
||||
let storage_ota = mk_static!(FlashStorage, FlashStorage::new());
|
||||
let pt =
|
||||
esp_bootloader_esp_idf::partitions::read_partition_table(storage_ota, tablebuffer)?;
|
||||
|
||||
// List all partitions - this is just FYI
|
||||
for i in 0..pt.len() {
|
||||
info!("{:?}", pt.get_partition(i));
|
||||
}
|
||||
let bullshit = MutexFlashStorage {
|
||||
inner: Arc::new(CriticalSectionMutex::new(RefCell::new(FlashStorage::new(
|
||||
peripherals.FLASH,
|
||||
)))),
|
||||
};
|
||||
let flash_storage = mk_static!(MutexFlashStorage, bullshit.clone());
|
||||
let flash_storage_2 = mk_static!(MutexFlashStorage, bullshit.clone());
|
||||
let flash_storage_3 = mk_static!(MutexFlashStorage, bullshit.clone());
|
||||
|
||||
let pt =
|
||||
esp_bootloader_esp_idf::partitions::read_partition_table(flash_storage, tablebuffer)?;
|
||||
|
||||
let ota_data = mk_static!(
|
||||
PartitionEntry,
|
||||
pt.find_partition(esp_bootloader_esp_idf::partitions::PartitionType::Data(
|
||||
@@ -320,34 +366,39 @@ impl PlantHal {
|
||||
.expect("No OTA data partition found")
|
||||
);
|
||||
|
||||
let ota_data = mk_static!(
|
||||
FlashRegion<FlashStorage>,
|
||||
ota_data.as_embedded_storage(storage_ota)
|
||||
);
|
||||
let mut ota_data = ota_data.as_embedded_storage(mk_static!(
|
||||
RmwNorFlashStorage<&mut MutexFlashStorage>,
|
||||
RmwNorFlashStorage::new(flash_storage_2, mk_static!([u8; 4096], [0_u8; 4096]))
|
||||
));
|
||||
|
||||
let mut ota = esp_bootloader_esp_idf::ota::Ota::new(ota_data)?;
|
||||
let state_0 = ota_state(AppPartitionSubType::Ota0, &mut ota_data);
|
||||
let state_1 = ota_state(AppPartitionSubType::Ota1, &mut ota_data);
|
||||
let mut ota = Ota::new(ota_data, 2)?;
|
||||
let running = get_current_slot(&pt, &mut ota)?;
|
||||
let target = next_partition(running)?;
|
||||
|
||||
let ota_partition = match ota.current_slot()? {
|
||||
Slot::None => {
|
||||
panic!("No OTA slot active?");
|
||||
info!("Currently running OTA slot: {running:?}");
|
||||
info!("Updates will be stored in OTA slot: {target:?}");
|
||||
info!("Slot0 state: {state_0:?}");
|
||||
info!("Slot1 state: {state_1:?}");
|
||||
|
||||
//get current_state and next_state here!
|
||||
let ota_target = match target {
|
||||
AppPartitionSubType::Ota0 => pt
|
||||
.find_partition(PartitionType::App(AppPartitionSubType::Ota0))?
|
||||
.context("Partition table invalid no ota0")?,
|
||||
AppPartitionSubType::Ota1 => pt
|
||||
.find_partition(PartitionType::App(AppPartitionSubType::Ota1))?
|
||||
.context("Partition table invalid no ota1")?,
|
||||
_ => {
|
||||
bail!("Invalid target partition");
|
||||
}
|
||||
Slot::Slot0 => pt
|
||||
.find_partition(esp_bootloader_esp_idf::partitions::PartitionType::App(
|
||||
AppPartitionSubType::Ota0,
|
||||
))?
|
||||
.expect("No OTA slot0 found"),
|
||||
Slot::Slot1 => pt
|
||||
.find_partition(esp_bootloader_esp_idf::partitions::PartitionType::App(
|
||||
AppPartitionSubType::Ota1,
|
||||
))?
|
||||
.expect("No OTA slot1 found"),
|
||||
};
|
||||
|
||||
let ota_next = mk_static!(PartitionEntry, ota_partition);
|
||||
let storage_ota = mk_static!(FlashStorage, FlashStorage::new());
|
||||
let ota_next = mk_static!(
|
||||
FlashRegion<FlashStorage>,
|
||||
ota_next.as_embedded_storage(storage_ota)
|
||||
let ota_target = mk_static!(PartitionEntry, ota_target);
|
||||
let ota_target = mk_static!(
|
||||
FlashRegion<MutexFlashStorage>,
|
||||
ota_target.as_embedded_storage(flash_storage)
|
||||
);
|
||||
|
||||
let data_partition = pt
|
||||
@@ -357,39 +408,53 @@ impl PlantHal {
|
||||
.expect("Data partition with littlefs not found");
|
||||
let data_partition = mk_static!(PartitionEntry, data_partition);
|
||||
|
||||
let storage_data = mk_static!(FlashStorage, FlashStorage::new());
|
||||
let data = mk_static!(
|
||||
FlashRegion<FlashStorage>,
|
||||
data_partition.as_embedded_storage(storage_data)
|
||||
FlashRegion<MutexFlashStorage>,
|
||||
data_partition.as_embedded_storage(flash_storage_3)
|
||||
);
|
||||
let lfs2filesystem = mk_static!(LittleFs2Filesystem, LittleFs2Filesystem { storage: data });
|
||||
let alloc = mk_static!(Allocation<LittleFs2Filesystem>, lfs2Filesystem::allocate());
|
||||
if lfs2filesystem.is_mountable() {
|
||||
log::info!("Littlefs2 filesystem is mountable");
|
||||
info!("Littlefs2 filesystem is mountable");
|
||||
} else {
|
||||
match lfs2filesystem.format() {
|
||||
Result::Ok(..) => {
|
||||
log::info!("Littlefs2 filesystem is formatted");
|
||||
Ok(..) => {
|
||||
info!("Littlefs2 filesystem is formatted");
|
||||
}
|
||||
Err(err) => {
|
||||
bail!("Littlefs2 filesystem could not be formatted: {:?}", err);
|
||||
error!("Littlefs2 filesystem could not be formatted: {err:?}");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[allow(clippy::arc_with_non_send_sync)]
|
||||
let fs = Arc::new(Mutex::new(
|
||||
lfs2Filesystem::mount(alloc, lfs2filesystem).expect("Could not mount lfs2 filesystem"),
|
||||
));
|
||||
|
||||
|
||||
let uart0 =
|
||||
Uart::new(peripherals.UART0, UartConfig::default()).map_err(|_| FatError::String {
|
||||
error: "Uart creation failed".to_string(),
|
||||
})?;
|
||||
|
||||
let ap = interfaces.access_point;
|
||||
let sta = interfaces.station;
|
||||
let mut esp = Esp {
|
||||
fs,
|
||||
rng,
|
||||
controller: Arc::new(Mutex::new(controller)),
|
||||
interfaces: Some(interfaces),
|
||||
interface_sta: Some(sta),
|
||||
interface_ap: Some(ap),
|
||||
boot_button,
|
||||
mqtt_client: None,
|
||||
wake_gpio1,
|
||||
ota,
|
||||
ota_next,
|
||||
ota_target,
|
||||
current: running,
|
||||
slot0_state: state_0,
|
||||
slot1_state: state_1,
|
||||
uart0,
|
||||
rtc: rtc_peripheral,
|
||||
};
|
||||
|
||||
//init,reset rtc memory depending on cause
|
||||
@@ -399,24 +464,25 @@ impl PlantHal {
|
||||
None => "unknown",
|
||||
Some(reason) => match reason {
|
||||
SocResetReason::ChipPowerOn => "power on",
|
||||
SocResetReason::CoreSw => "software reset",
|
||||
SocResetReason::CoreDeepSleep => "deep sleep",
|
||||
SocResetReason::CoreSDIO => "sdio reset",
|
||||
SocResetReason::CoreMwdt0 => "Watchdog Main",
|
||||
SocResetReason::CoreMwdt1 => "Watchdog 1",
|
||||
SocResetReason::CoreRtcWdt => "Watchdog RTC",
|
||||
SocResetReason::Cpu0Mwdt0 => "Watchdog MCpu0",
|
||||
SocResetReason::Cpu0Sw => "software reset cpu0",
|
||||
SocResetReason::SysRtcWdt => "Watchdog Sys rtc",
|
||||
SocResetReason::Cpu0Mwdt1 => "cpu0 mwdt1",
|
||||
SocResetReason::SysSuperWdt => "Watchdog Super",
|
||||
SocResetReason::Cpu0RtcWdt => {
|
||||
init_rtc_store = true;
|
||||
"Watchdog RTC cpu0"
|
||||
}
|
||||
SocResetReason::CoreSw => "software reset",
|
||||
SocResetReason::CoreDeepSleep => "deep sleep",
|
||||
SocResetReason::SysBrownOut => "sys brown out",
|
||||
SocResetReason::SysRtcWdt => "Watchdog Sys rtc",
|
||||
SocResetReason::Cpu0Mwdt1 => "cpu0 mwdt1",
|
||||
SocResetReason::SysSuperWdt => "Watchdog Super",
|
||||
SocResetReason::CoreEfuseCrc => "core efuse crc",
|
||||
SocResetReason::CoreUsbUart => {
|
||||
//TODO still required? or via button ignore? to_config_mode = true;
|
||||
to_config_mode = true;
|
||||
"core usb uart"
|
||||
}
|
||||
@@ -424,24 +490,21 @@ impl PlantHal {
|
||||
SocResetReason::Cpu0JtagCpu => "cpu0 jtag cpu",
|
||||
},
|
||||
};
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
LogMessage::ResetReason,
|
||||
init_rtc_store as u32,
|
||||
to_config_mode as u32,
|
||||
"",
|
||||
&format!("{reasons:?}"),
|
||||
)
|
||||
.await;
|
||||
log(
|
||||
LogMessage::ResetReason,
|
||||
init_rtc_store as u32,
|
||||
to_config_mode as u32,
|
||||
"",
|
||||
&format!("{reasons:?}"),
|
||||
);
|
||||
|
||||
|
||||
esp.init_rtc_deepsleep_memory(init_rtc_store, to_config_mode)
|
||||
.await;
|
||||
|
||||
let config = esp.load_config().await;
|
||||
|
||||
log::info!("Init rtc driver");
|
||||
info!("Init rtc driver");
|
||||
|
||||
let sda = peripherals.GPIO20;
|
||||
let scl = peripherals.GPIO19;
|
||||
@@ -459,26 +522,30 @@ impl PlantHal {
|
||||
RefCell<I2c<Blocking>>,
|
||||
> = CriticalSectionMutex::new(RefCell::new(i2c));
|
||||
|
||||
|
||||
I2C_DRIVER.init(i2c_bus).expect("Could not init i2c driver");
|
||||
|
||||
let i2c_bus = I2C_DRIVER.get().await;
|
||||
let rtc_device = I2cDevice::new(&i2c_bus);
|
||||
let eeprom_device = I2cDevice::new(&i2c_bus);
|
||||
let rtc_device = I2cDevice::new(i2c_bus);
|
||||
let mut bms_device = I2cDevice::new(i2c_bus);
|
||||
let eeprom_device = I2cDevice::new(i2c_bus);
|
||||
|
||||
|
||||
let mut rtc: Ds323x<
|
||||
I2cInterface<I2cDevice<CriticalSectionRawMutex, I2c<Blocking>>>,
|
||||
DS3231,
|
||||
> = Ds323x::new_ds3231(rtc_device);
|
||||
|
||||
|
||||
info!("Init rtc eeprom driver");
|
||||
let eeprom = Eeprom24x::new_24x32(eeprom_device, SlaveAddr::Alternative(true, true, true));
|
||||
let rtc_time = rtc.datetime();
|
||||
match rtc_time {
|
||||
Ok(tt) => {
|
||||
log::info!("Rtc Module reports time at UTC {}", tt);
|
||||
info!("Rtc Module reports time at UTC {tt}");
|
||||
}
|
||||
Err(err) => {
|
||||
log::info!("Rtc Module could not be read {:?}", err);
|
||||
info!("Rtc Module could not be read {err:?}");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -493,72 +560,51 @@ impl PlantHal {
|
||||
Box::new(DS3231Module { rtc, storage }) as Box<dyn RTCModuleInteraction + Send>;
|
||||
|
||||
let hal = match config {
|
||||
Result::Ok(config) => {
|
||||
Ok(config) => {
|
||||
let battery_interaction: Box<dyn BatteryInteraction + Send> =
|
||||
match config.hardware.battery {
|
||||
BatteryBoardVersion::Disabled => Box::new(NoBatteryMonitor {}),
|
||||
BatteryBoardVersion::BQ34Z100G1 => {
|
||||
let battery_device = I2cDevice::new(I2C_DRIVER.get().await);
|
||||
let mut battery_driver = Bq34z100g1Driver {
|
||||
i2c: battery_device,
|
||||
delay: Delay::new(),
|
||||
flash_block_data: [0; 32],
|
||||
};
|
||||
let status = print_battery_bq34z100(&mut battery_driver);
|
||||
match status {
|
||||
Ok(_) => {}
|
||||
Err(err) => {
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
LogMessage::BatteryCommunicationError,
|
||||
0u32,
|
||||
0,
|
||||
"",
|
||||
&format!("{err:?})"),
|
||||
)
|
||||
.await;
|
||||
}
|
||||
}
|
||||
Box::new(BQ34Z100G1 { battery_driver })
|
||||
}
|
||||
BatteryBoardVersion::WchI2cSlave => {
|
||||
// TODO use correct implementation once availible
|
||||
Box::new(NoBatteryMonitor {})
|
||||
let version = ProtocolVersion::read_from_i2c(&mut bms_device);
|
||||
let version_val = match version {
|
||||
Ok(v) => unsafe { core::mem::transmute::<ProtocolVersion, u32>(v) },
|
||||
Err(_) => 0,
|
||||
};
|
||||
if version_val == 1 {
|
||||
//Box::new(WCHI2CSlave { i2c: bms_device })
|
||||
// todo fix the type above
|
||||
Box::new(NoBatteryMonitor {})
|
||||
} else {
|
||||
//todo should be an error variant instead?
|
||||
Box::new(NoBatteryMonitor {})
|
||||
}
|
||||
}
|
||||
BatteryBoardVersion::BQ34Z100G1 => Box::new(NoBatteryMonitor {}),
|
||||
};
|
||||
|
||||
let board_hal: Box<dyn BoardInteraction + Send> = match config.hardware.board {
|
||||
BoardVersion::INITIAL => {
|
||||
initial_hal::create_initial_board(free_pins, config, esp)?
|
||||
}
|
||||
// BoardVersion::V3 => {
|
||||
// v3_hal::create_v3(free_pins, esp, config, battery_interaction, rtc_module)?
|
||||
// }
|
||||
BoardVersion::V3 => {
|
||||
v3_hal::create_v3(free_pins, esp, config, battery_interaction, rtc_module)?
|
||||
}
|
||||
BoardVersion::V4 => {
|
||||
v4_hal::create_v4(free_pins, esp, config, battery_interaction, rtc_module)
|
||||
.await?
|
||||
}
|
||||
_ => {
|
||||
bail!("Unknown board version");
|
||||
}
|
||||
};
|
||||
|
||||
HAL { board_hal }
|
||||
}
|
||||
Err(err) => {
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
LogMessage::ConfigModeMissingConfig,
|
||||
0,
|
||||
0,
|
||||
"",
|
||||
&err.to_string(),
|
||||
)
|
||||
.await;
|
||||
log(
|
||||
LogMessage::ConfigModeMissingConfig,
|
||||
0,
|
||||
0,
|
||||
"",
|
||||
&err.to_string(),
|
||||
);
|
||||
HAL {
|
||||
board_hal: initial_hal::create_initial_board(
|
||||
free_pins,
|
||||
@@ -571,24 +617,13 @@ impl PlantHal {
|
||||
|
||||
Ok(Mutex::new(hal))
|
||||
}
|
||||
}
|
||||
|
||||
pub async fn esp_time() -> DateTime<Utc> {
|
||||
DateTime::from_timestamp_micros(TIME_ACCESS.get().await.current_time_us() as i64).unwrap()
|
||||
}
|
||||
|
||||
pub async fn esp_set_time(time: DateTime<FixedOffset>) {
|
||||
TIME_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.set_current_time_us(time.timestamp_micros() as u64);
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.set_rtc_time(&time.to_utc())
|
||||
.await;
|
||||
/// Feed the watchdog timer to prevent system reset
|
||||
pub fn feed_watchdog() {
|
||||
if let Some(wdt_mutex) = WATCHDOG.try_get() {
|
||||
wdt_mutex.lock(|cell| {
|
||||
cell.borrow_mut().feed();
|
||||
});
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
65
rust/src/hal/shared_flash.rs
Normal file
65
rust/src/hal/shared_flash.rs
Normal file
@@ -0,0 +1,65 @@
|
||||
use alloc::sync::Arc;
|
||||
use core::cell::RefCell;
|
||||
use core::ops::{Deref, DerefMut};
|
||||
use embassy_sync::blocking_mutex::CriticalSectionMutex;
|
||||
use embedded_storage::nor_flash::{ErrorType, NorFlash, ReadNorFlash};
|
||||
use embedded_storage::ReadStorage;
|
||||
use esp_storage::{FlashStorage, FlashStorageError};
|
||||
use log::info;
|
||||
|
||||
#[derive(Clone)]
|
||||
pub struct MutexFlashStorage {
|
||||
pub(crate) inner: Arc<CriticalSectionMutex<RefCell<FlashStorage<'static>>>>,
|
||||
}
|
||||
|
||||
impl ReadStorage for MutexFlashStorage {
|
||||
type Error = FlashStorageError;
|
||||
|
||||
fn read(&mut self, offset: u32, bytes: &mut [u8]) -> Result<(), FlashStorageError> {
|
||||
self.inner
|
||||
.lock(|f| ReadStorage::read(f.borrow_mut().deref_mut(), offset, bytes))
|
||||
}
|
||||
|
||||
fn capacity(&self) -> usize {
|
||||
self.inner
|
||||
.lock(|f| ReadStorage::capacity(f.borrow().deref()))
|
||||
}
|
||||
}
|
||||
|
||||
impl embedded_storage::Storage for MutexFlashStorage {
|
||||
fn write(&mut self, offset: u32, bytes: &[u8]) -> Result<(), Self::Error> {
|
||||
NorFlash::write(self, offset, bytes)
|
||||
}
|
||||
}
|
||||
|
||||
impl ErrorType for MutexFlashStorage {
|
||||
type Error = FlashStorageError;
|
||||
}
|
||||
|
||||
impl ReadNorFlash for MutexFlashStorage {
|
||||
const READ_SIZE: usize = 1;
|
||||
|
||||
fn read(&mut self, offset: u32, bytes: &mut [u8]) -> Result<(), Self::Error> {
|
||||
ReadStorage::read(self, offset, bytes)
|
||||
}
|
||||
|
||||
fn capacity(&self) -> usize {
|
||||
ReadStorage::capacity(self)
|
||||
}
|
||||
}
|
||||
|
||||
impl NorFlash for MutexFlashStorage {
|
||||
const WRITE_SIZE: usize = 1;
|
||||
const ERASE_SIZE: usize = 4096;
|
||||
|
||||
fn erase(&mut self, from: u32, to: u32) -> Result<(), Self::Error> {
|
||||
info!("Erasing flash from 0x{:x} to 0x{:x}", from, to);
|
||||
self.inner
|
||||
.lock(|f| NorFlash::erase(f.borrow_mut().deref_mut(), from, to))
|
||||
}
|
||||
|
||||
fn write(&mut self, offset: u32, bytes: &[u8]) -> Result<(), Self::Error> {
|
||||
self.inner
|
||||
.lock(|f| NorFlash::write(f.borrow_mut().deref_mut(), offset, bytes))
|
||||
}
|
||||
}
|
||||
451
rust/src/hal/v3_hal.rs
Normal file
451
rust/src/hal/v3_hal.rs
Normal file
@@ -0,0 +1,451 @@
|
||||
use crate::bail;
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::esp::{hold_disable, hold_enable};
|
||||
use crate::hal::rtc::RTCModuleInteraction;
|
||||
use crate::hal::v3_shift_register::ShiftRegister40;
|
||||
use crate::hal::water::TankSensor;
|
||||
use crate::hal::{BoardInteraction, FreePeripherals, Sensor, PLANT_COUNT};
|
||||
use crate::log::{log, LogMessage, LOG_ACCESS};
|
||||
use crate::{
|
||||
config::PlantControllerConfig,
|
||||
hal::{battery::BatteryInteraction, esp::Esp},
|
||||
};
|
||||
use alloc::boxed::Box;
|
||||
use alloc::format;
|
||||
use alloc::string::ToString;
|
||||
use async_trait::async_trait;
|
||||
use chrono::{DateTime, FixedOffset, Utc};
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use embassy_time::Timer;
|
||||
use embedded_hal::digital::OutputPin as _;
|
||||
use esp_hal::gpio::{Flex, Input, InputConfig, Level, Output, OutputConfig, Pull};
|
||||
use esp_hal::pcnt::channel::CtrlMode::Keep;
|
||||
use esp_hal::pcnt::channel::EdgeMode;
|
||||
use esp_hal::pcnt::channel::EdgeMode::{Hold, Increment};
|
||||
use esp_hal::pcnt::unit::Unit;
|
||||
use measurements::{Current, Voltage};
|
||||
|
||||
const PUMP8_BIT: usize = 0;
|
||||
const PUMP1_BIT: usize = 1;
|
||||
const PUMP2_BIT: usize = 2;
|
||||
const PUMP3_BIT: usize = 3;
|
||||
const PUMP4_BIT: usize = 4;
|
||||
const PUMP5_BIT: usize = 5;
|
||||
const PUMP6_BIT: usize = 6;
|
||||
const PUMP7_BIT: usize = 7;
|
||||
const MS_0: usize = 8;
|
||||
const MS_4: usize = 9;
|
||||
const MS_2: usize = 10;
|
||||
const MS_3: usize = 11;
|
||||
const MS_1: usize = 13;
|
||||
const SENSOR_ON: usize = 12;
|
||||
|
||||
const SENSOR_A_1: u8 = 7;
|
||||
const SENSOR_A_2: u8 = 6;
|
||||
const SENSOR_A_3: u8 = 5;
|
||||
const SENSOR_A_4: u8 = 4;
|
||||
const SENSOR_A_5: u8 = 3;
|
||||
const SENSOR_A_6: u8 = 2;
|
||||
const SENSOR_A_7: u8 = 1;
|
||||
const SENSOR_A_8: u8 = 0;
|
||||
|
||||
const SENSOR_B_1: u8 = 8;
|
||||
const SENSOR_B_2: u8 = 9;
|
||||
const SENSOR_B_3: u8 = 10;
|
||||
const SENSOR_B_4: u8 = 11;
|
||||
const SENSOR_B_5: u8 = 12;
|
||||
const SENSOR_B_6: u8 = 13;
|
||||
const SENSOR_B_7: u8 = 14;
|
||||
const SENSOR_B_8: u8 = 15;
|
||||
|
||||
const CHARGING: usize = 14;
|
||||
const AWAKE: usize = 15;
|
||||
|
||||
const FAULT_3: usize = 16;
|
||||
const FAULT_8: usize = 17;
|
||||
const FAULT_7: usize = 18;
|
||||
const FAULT_6: usize = 19;
|
||||
const FAULT_5: usize = 20;
|
||||
const FAULT_4: usize = 21;
|
||||
const FAULT_1: usize = 22;
|
||||
const FAULT_2: usize = 23;
|
||||
|
||||
const REPEAT_MOIST_MEASURE: usize = 1;
|
||||
|
||||
pub struct V3<'a> {
|
||||
config: PlantControllerConfig,
|
||||
battery_monitor: Box<dyn BatteryInteraction + Send>,
|
||||
rtc_module: Box<dyn RTCModuleInteraction + Send>,
|
||||
esp: Esp<'a>,
|
||||
shift_register:
|
||||
Mutex<CriticalSectionRawMutex, ShiftRegister40<Output<'a>, Output<'a>, Output<'a>>>,
|
||||
_shift_register_enable_invert: Output<'a>,
|
||||
tank_sensor: TankSensor<'a>,
|
||||
solar_is_day: Input<'a>,
|
||||
light: Output<'a>,
|
||||
main_pump: Output<'a>,
|
||||
general_fault: Output<'a>,
|
||||
pub signal_counter: Unit<'static, 0>,
|
||||
}
|
||||
|
||||
pub(crate) fn create_v3(
|
||||
peripherals: FreePeripherals<'static>,
|
||||
esp: Esp<'static>,
|
||||
config: PlantControllerConfig,
|
||||
battery_monitor: Box<dyn BatteryInteraction + Send>,
|
||||
rtc_module: Box<dyn RTCModuleInteraction + Send>,
|
||||
) -> Result<Box<dyn BoardInteraction<'static> + Send + 'static>, FatError> {
|
||||
log::info!("Start v3");
|
||||
let clock = Output::new(peripherals.gpio15, Level::Low, OutputConfig::default());
|
||||
let latch = Output::new(peripherals.gpio3, Level::Low, OutputConfig::default());
|
||||
let data = Output::new(peripherals.gpio23, Level::Low, OutputConfig::default());
|
||||
let shift_register = ShiftRegister40::new(clock, latch, data);
|
||||
//disable all
|
||||
for mut pin in shift_register.decompose() {
|
||||
let _ = pin.set_low();
|
||||
}
|
||||
|
||||
// Set always-on status bits
|
||||
let _ = shift_register.decompose()[AWAKE].set_high();
|
||||
let _ = shift_register.decompose()[CHARGING].set_high();
|
||||
|
||||
// Multiplexer defaults: ms0..ms3 low, ms4 high (disabled)
|
||||
let _ = shift_register.decompose()[MS_0].set_low();
|
||||
let _ = shift_register.decompose()[MS_1].set_low();
|
||||
let _ = shift_register.decompose()[MS_2].set_low();
|
||||
let _ = shift_register.decompose()[MS_3].set_low();
|
||||
let _ = shift_register.decompose()[MS_4].set_high();
|
||||
|
||||
let one_wire_pin = Flex::new(peripherals.gpio18);
|
||||
let tank_power_pin = Output::new(peripherals.gpio11, Level::Low, OutputConfig::default());
|
||||
|
||||
let flow_sensor_pin = Input::new(
|
||||
peripherals.gpio4,
|
||||
InputConfig::default().with_pull(Pull::Up),
|
||||
);
|
||||
|
||||
let tank_sensor = TankSensor::create(
|
||||
one_wire_pin,
|
||||
peripherals.adc1,
|
||||
peripherals.gpio5,
|
||||
tank_power_pin,
|
||||
flow_sensor_pin,
|
||||
peripherals.pcnt1,
|
||||
)?;
|
||||
|
||||
let solar_is_day = Input::new(peripherals.gpio7, InputConfig::default());
|
||||
let light = Output::new(peripherals.gpio10, Level::Low, OutputConfig::default());
|
||||
let mut main_pump = Output::new(peripherals.gpio2, Level::Low, OutputConfig::default());
|
||||
main_pump.set_low();
|
||||
let mut general_fault = Output::new(peripherals.gpio6, Level::Low, OutputConfig::default());
|
||||
general_fault.set_low();
|
||||
|
||||
hold_disable(21);
|
||||
let mut shift_register_enable_invert =
|
||||
Output::new(peripherals.gpio21, Level::Low, OutputConfig::default());
|
||||
shift_register_enable_invert.set_low();
|
||||
hold_enable(21);
|
||||
|
||||
let signal_counter = peripherals.pcnt0;
|
||||
|
||||
signal_counter.set_low_limit(None)?;
|
||||
signal_counter.set_high_limit(Some(i16::MAX))?;
|
||||
|
||||
let ch0 = &signal_counter.channel0;
|
||||
let edge_pin = Input::new(peripherals.gpio22, InputConfig::default());
|
||||
ch0.set_edge_signal(edge_pin.peripheral_input());
|
||||
ch0.set_input_mode(Hold, Increment);
|
||||
ch0.set_ctrl_mode(Keep, Keep);
|
||||
signal_counter.listen();
|
||||
|
||||
Ok(Box::new(V3 {
|
||||
config,
|
||||
battery_monitor,
|
||||
rtc_module,
|
||||
esp,
|
||||
shift_register: Mutex::new(shift_register),
|
||||
_shift_register_enable_invert: shift_register_enable_invert,
|
||||
tank_sensor,
|
||||
solar_is_day,
|
||||
light,
|
||||
main_pump,
|
||||
general_fault,
|
||||
signal_counter,
|
||||
}))
|
||||
}
|
||||
|
||||
#[async_trait]
|
||||
impl<'a> BoardInteraction<'a> for V3<'a> {
|
||||
fn get_tank_sensor(&mut self) -> Result<&mut TankSensor<'a>, FatError> {
|
||||
Ok(&mut self.tank_sensor)
|
||||
}
|
||||
|
||||
fn get_esp(&mut self) -> &mut Esp<'a> {
|
||||
&mut self.esp
|
||||
}
|
||||
|
||||
fn get_config(&mut self) -> &PlantControllerConfig {
|
||||
&self.config
|
||||
}
|
||||
|
||||
fn get_battery_monitor(&mut self) -> &mut Box<dyn BatteryInteraction + Send> {
|
||||
&mut self.battery_monitor
|
||||
}
|
||||
|
||||
fn get_rtc_module(&mut self) -> &mut Box<dyn RTCModuleInteraction + Send> {
|
||||
&mut self.rtc_module
|
||||
}
|
||||
|
||||
async fn get_time(&mut self) -> DateTime<Utc> {
|
||||
self.esp.get_time()
|
||||
}
|
||||
|
||||
async fn set_time(&mut self, time: &DateTime<FixedOffset>) -> FatResult<()> {
|
||||
self.rtc_module.set_rtc_time(&time.to_utc()).await?;
|
||||
self.esp.set_time(time.to_utc());
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError> {
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
if charging {
|
||||
let _ = shift_register.decompose()[CHARGING].set_high();
|
||||
} else {
|
||||
let _ = shift_register.decompose()[CHARGING].set_low();
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn deep_sleep_ms(&mut self, duration_in_ms: u64) -> ! {
|
||||
let _ = self.shift_register.lock().await.decompose()[AWAKE].set_low();
|
||||
self.esp.deep_sleep_ms(duration_in_ms)
|
||||
}
|
||||
|
||||
fn is_day(&self) -> bool {
|
||||
self.solar_is_day.is_high()
|
||||
}
|
||||
|
||||
async fn light(&mut self, enable: bool) -> Result<(), FatError> {
|
||||
hold_disable(10);
|
||||
if enable {
|
||||
self.light.set_high();
|
||||
} else {
|
||||
self.light.set_low();
|
||||
}
|
||||
hold_enable(10);
|
||||
Ok(())
|
||||
}
|
||||
async fn pump(&mut self, plant: usize, enable: bool) -> Result<(), FatError> {
|
||||
if enable {
|
||||
self.main_pump.set_high();
|
||||
}
|
||||
|
||||
let index = match plant {
|
||||
0 => PUMP1_BIT,
|
||||
1 => PUMP2_BIT,
|
||||
2 => PUMP3_BIT,
|
||||
3 => PUMP4_BIT,
|
||||
4 => PUMP5_BIT,
|
||||
5 => PUMP6_BIT,
|
||||
6 => PUMP7_BIT,
|
||||
7 => PUMP8_BIT,
|
||||
_ => bail!("Invalid pump {plant}"),
|
||||
};
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
if enable {
|
||||
let _ = shift_register.decompose()[index].set_high();
|
||||
} else {
|
||||
let _ = shift_register.decompose()[index].set_low();
|
||||
}
|
||||
|
||||
if !enable {
|
||||
self.main_pump.set_low();
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn pump_current(&mut self, _plant: usize) -> Result<Current, FatError> {
|
||||
bail!("Not implemented in v3")
|
||||
}
|
||||
|
||||
async fn fault(&mut self, plant: usize, enable: bool) -> Result<(), FatError> {
|
||||
let index = match plant {
|
||||
0 => FAULT_1,
|
||||
1 => FAULT_2,
|
||||
2 => FAULT_3,
|
||||
3 => FAULT_4,
|
||||
4 => FAULT_5,
|
||||
5 => FAULT_6,
|
||||
6 => FAULT_7,
|
||||
7 => FAULT_8,
|
||||
_ => panic!("Invalid plant id {}", plant),
|
||||
};
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
if enable {
|
||||
let _ = shift_register.decompose()[index].set_high();
|
||||
} else {
|
||||
let _ = shift_register.decompose()[index].set_low();
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> Result<f32, FatError> {
|
||||
let mut results = [0_f32; REPEAT_MOIST_MEASURE];
|
||||
for repeat in 0..REPEAT_MOIST_MEASURE {
|
||||
self.signal_counter.pause();
|
||||
self.signal_counter.clear();
|
||||
//Disable all
|
||||
{
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
shift_register.decompose()[MS_4].set_high()?;
|
||||
}
|
||||
|
||||
let sensor_channel = match sensor {
|
||||
Sensor::A => match plant {
|
||||
0 => SENSOR_A_1,
|
||||
1 => SENSOR_A_2,
|
||||
2 => SENSOR_A_3,
|
||||
3 => SENSOR_A_4,
|
||||
4 => SENSOR_A_5,
|
||||
5 => SENSOR_A_6,
|
||||
6 => SENSOR_A_7,
|
||||
7 => SENSOR_A_8,
|
||||
_ => bail!("Invalid plant id {}", plant),
|
||||
},
|
||||
Sensor::B => match plant {
|
||||
0 => SENSOR_B_1,
|
||||
1 => SENSOR_B_2,
|
||||
2 => SENSOR_B_3,
|
||||
3 => SENSOR_B_4,
|
||||
4 => SENSOR_B_5,
|
||||
5 => SENSOR_B_6,
|
||||
6 => SENSOR_B_7,
|
||||
7 => SENSOR_B_8,
|
||||
_ => bail!("Invalid plant id {}", plant),
|
||||
},
|
||||
};
|
||||
|
||||
let is_bit_set = |b: u8| -> bool { sensor_channel & (1 << b) != 0 };
|
||||
{
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
let pin_0 = &mut shift_register.decompose()[MS_0];
|
||||
let pin_1 = &mut shift_register.decompose()[MS_1];
|
||||
let pin_2 = &mut shift_register.decompose()[MS_2];
|
||||
let pin_3 = &mut shift_register.decompose()[MS_3];
|
||||
if is_bit_set(0) {
|
||||
pin_0.set_high()?;
|
||||
} else {
|
||||
pin_0.set_low()?;
|
||||
}
|
||||
if is_bit_set(1) {
|
||||
pin_1.set_high()?;
|
||||
} else {
|
||||
pin_1.set_low()?;
|
||||
}
|
||||
if is_bit_set(2) {
|
||||
pin_2.set_high()?;
|
||||
} else {
|
||||
pin_2.set_low()?;
|
||||
}
|
||||
if is_bit_set(3) {
|
||||
pin_3.set_high()?;
|
||||
} else {
|
||||
pin_3.set_low()?;
|
||||
}
|
||||
|
||||
shift_register.decompose()[MS_4].set_low()?;
|
||||
shift_register.decompose()[SENSOR_ON].set_high()?;
|
||||
}
|
||||
let measurement = 100; //how long to measure and then extrapolate to hz
|
||||
let factor = 1000f32 / measurement as f32; //scale raw cound by this number to get hz
|
||||
|
||||
//give some time to stabilize
|
||||
Timer::after_millis(10).await;
|
||||
self.signal_counter.resume();
|
||||
Timer::after_millis(measurement).await;
|
||||
self.signal_counter.pause();
|
||||
{
|
||||
let shift_register = self.shift_register.lock().await;
|
||||
shift_register.decompose()[MS_4].set_high()?;
|
||||
shift_register.decompose()[SENSOR_ON].set_low()?;
|
||||
}
|
||||
Timer::after_millis(10).await;
|
||||
let unscaled = self.signal_counter.value();
|
||||
let hz = unscaled as f32 * factor;
|
||||
log(
|
||||
LogMessage::RawMeasure,
|
||||
unscaled as u32,
|
||||
hz as u32,
|
||||
&plant.to_string(),
|
||||
&format!("{sensor:?}"),
|
||||
);
|
||||
results[repeat] = hz;
|
||||
}
|
||||
results.sort_by(|a, b| a.partial_cmp(b).unwrap()); // floats don't seem to implement total_ord
|
||||
|
||||
let mid = results.len() / 2;
|
||||
let median = results[mid];
|
||||
Ok(median)
|
||||
}
|
||||
|
||||
async fn general_fault(&mut self, enable: bool) {
|
||||
hold_disable(6);
|
||||
if enable {
|
||||
self.general_fault.set_high();
|
||||
} else {
|
||||
self.general_fault.set_low();
|
||||
}
|
||||
hold_enable(6);
|
||||
}
|
||||
|
||||
async fn test(&mut self) -> Result<(), FatError> {
|
||||
self.general_fault(true).await;
|
||||
Timer::after_millis(100).await;
|
||||
self.general_fault(false).await;
|
||||
Timer::after_millis(100).await;
|
||||
self.light(true).await?;
|
||||
Timer::after_millis(500).await;
|
||||
|
||||
self.light(false).await?;
|
||||
Timer::after_millis(500).await;
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.fault(i, true).await?;
|
||||
Timer::after_millis(500).await;
|
||||
self.fault(i, false).await?;
|
||||
Timer::after_millis(500).await;
|
||||
}
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.pump(i, true).await?;
|
||||
Timer::after_millis(100).await;
|
||||
self.pump(i, false).await?;
|
||||
Timer::after_millis(100).await;
|
||||
}
|
||||
for plant in 0..PLANT_COUNT {
|
||||
let a = self.measure_moisture_hz(plant, Sensor::A).await;
|
||||
let b = self.measure_moisture_hz(plant, Sensor::B).await;
|
||||
let aa = match a {
|
||||
Ok(a) => a as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
let bb = match b {
|
||||
Ok(b) => b as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
log(LogMessage::TestSensor, aa, bb, &plant.to_string(), "");
|
||||
}
|
||||
Timer::after_millis(10).await;
|
||||
Ok(())
|
||||
}
|
||||
|
||||
fn set_config(&mut self, config: PlantControllerConfig) {
|
||||
self.config = config;
|
||||
}
|
||||
|
||||
async fn get_mptt_voltage(&mut self) -> Result<Voltage, FatError> {
|
||||
bail!("Not implemented in v3")
|
||||
}
|
||||
async fn get_mptt_current(&mut self) -> Result<Current, FatError> {
|
||||
bail!("Not implemented in v3")
|
||||
}
|
||||
}
|
||||
@@ -1,5 +1,5 @@
|
||||
//! Serial-in parallel-out shift register
|
||||
|
||||
#![allow(warnings)]
|
||||
use core::cell::RefCell;
|
||||
use core::convert::Infallible;
|
||||
use core::iter::Iterator;
|
||||
@@ -7,7 +7,7 @@ use core::mem::{self, MaybeUninit};
|
||||
use core::result::{Result, Result::Ok};
|
||||
use embedded_hal::digital::OutputPin;
|
||||
|
||||
trait ShiftRegisterInternal {
|
||||
trait ShiftRegisterInternal: Send {
|
||||
fn update(&self, index: usize, command: bool) -> Result<(), ()>;
|
||||
}
|
||||
|
||||
@@ -47,9 +47,9 @@ macro_rules! ShiftRegisterBuilder {
|
||||
/// Serial-in parallel-out shift register
|
||||
pub struct $name<Pin1, Pin2, Pin3>
|
||||
where
|
||||
Pin1: OutputPin,
|
||||
Pin2: OutputPin,
|
||||
Pin3: OutputPin,
|
||||
Pin1: OutputPin + Send,
|
||||
Pin2: OutputPin + Send,
|
||||
Pin3: OutputPin + Send,
|
||||
{
|
||||
clock: RefCell<Pin1>,
|
||||
latch: RefCell<Pin2>,
|
||||
@@ -59,9 +59,9 @@ macro_rules! ShiftRegisterBuilder {
|
||||
|
||||
impl<Pin1, Pin2, Pin3> ShiftRegisterInternal for $name<Pin1, Pin2, Pin3>
|
||||
where
|
||||
Pin1: OutputPin,
|
||||
Pin2: OutputPin,
|
||||
Pin3: OutputPin,
|
||||
Pin1: OutputPin + Send,
|
||||
Pin2: OutputPin + Send,
|
||||
Pin3: OutputPin + Send,
|
||||
{
|
||||
/// Sets the value of the shift register output at `index` to value `command`
|
||||
fn update(&self, index: usize, command: bool) -> Result<(), ()> {
|
||||
@@ -86,9 +86,9 @@ macro_rules! ShiftRegisterBuilder {
|
||||
|
||||
impl<Pin1, Pin2, Pin3> $name<Pin1, Pin2, Pin3>
|
||||
where
|
||||
Pin1: OutputPin,
|
||||
Pin2: OutputPin,
|
||||
Pin3: OutputPin,
|
||||
Pin1: OutputPin + Send,
|
||||
Pin2: OutputPin + Send,
|
||||
Pin3: OutputPin + Send,
|
||||
{
|
||||
/// Creates a new SIPO shift register from clock, latch, and data output pins
|
||||
pub fn new(clock: Pin1, latch: Pin2, data: Pin3) -> Self {
|
||||
@@ -1,23 +1,26 @@
|
||||
use crate::config::PlantControllerConfig;
|
||||
use crate::hal::battery::BatteryInteraction;
|
||||
use crate::hal::esp::Esp;
|
||||
use crate::hal::esp::{hold_disable, hold_enable, Esp};
|
||||
use crate::hal::rtc::RTCModuleInteraction;
|
||||
use crate::hal::water::TankSensor;
|
||||
use crate::hal::{BoardInteraction, FreePeripherals, Sensor, I2C_DRIVER, PLANT_COUNT};
|
||||
use alloc::boxed::Box;
|
||||
use alloc::string::ToString;
|
||||
use async_trait::async_trait;
|
||||
use chrono::{DateTime, FixedOffset, Utc};
|
||||
use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_time::Timer;
|
||||
use esp_hal::analog::adc::{Adc, AdcConfig, Attenuation};
|
||||
use esp_hal::{twai, Blocking};
|
||||
//use embedded_hal_bus::i2c::MutexDevice;
|
||||
use crate::bail;
|
||||
use crate::hal::v4_sensor::{SensorImpl, SensorInteraction};
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::v4_sensor::{SensorImpl, SensorInteraction};
|
||||
use crate::log::{LogMessage, LOG_ACCESS};
|
||||
use esp_hal::gpio::{Flex, Input, InputConfig, Level, Output, OutputConfig, Pull};
|
||||
use esp_hal::i2c::master::I2c;
|
||||
use esp_hal::pcnt::channel::CtrlMode::Keep;
|
||||
use esp_hal::pcnt::channel::EdgeMode::{Hold, Increment};
|
||||
use esp_hal::pcnt::Pcnt;
|
||||
use esp_hal::twai::{EspTwaiFrame, StandardId, TwaiMode};
|
||||
use esp_println::println;
|
||||
@@ -28,7 +31,6 @@ use ina219::SyncIna219;
|
||||
use measurements::Resistance;
|
||||
use measurements::{Current, Voltage};
|
||||
use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface};
|
||||
use crate::log::{LogMessage, LOG_ACCESS};
|
||||
|
||||
const MPPT_CURRENT_SHUNT_OHMS: f64 = 0.05_f64;
|
||||
const TWAI_BAUDRATE: twai::BaudRate = twai::BaudRate::B125K;
|
||||
@@ -137,10 +139,6 @@ pub struct V4<'a> {
|
||||
extra2: Output<'a>,
|
||||
}
|
||||
|
||||
struct InputOutput<'a> {
|
||||
pin: Flex<'a>,
|
||||
}
|
||||
|
||||
pub(crate) async fn create_v4(
|
||||
peripherals: FreePeripherals<'static>,
|
||||
esp: Esp<'static>,
|
||||
@@ -179,28 +177,18 @@ pub(crate) async fn create_v4(
|
||||
let sensor = match sensor_expander.pin_into_output(GPIOBank::Bank0, 0) {
|
||||
Ok(_) => {
|
||||
log::info!("SensorExpander answered");
|
||||
//pulse counter version
|
||||
// let mut signal_counter = PcntDriver::new(
|
||||
// peripherals.pcnt0,
|
||||
// Some(peripherals.gpio22),
|
||||
// Option::<AnyInputPin>::None,
|
||||
// Option::<AnyInputPin>::None,
|
||||
// Option::<AnyInputPin>::None,
|
||||
// )?;
|
||||
//
|
||||
// signal_counter.channel_config(
|
||||
// PcntChannel::Channel0,
|
||||
// PinIndex::Pin0,
|
||||
// PinIndex::Pin1,
|
||||
// &PcntChannelConfig {
|
||||
// lctrl_mode: PcntControlMode::Keep,
|
||||
// hctrl_mode: PcntControlMode::Keep,
|
||||
// pos_mode: PcntCountMode::Increment,
|
||||
// neg_mode: PcntCountMode::Hold,
|
||||
// counter_h_lim: i16::MAX,
|
||||
// counter_l_lim: 0,
|
||||
// },
|
||||
// )?;
|
||||
|
||||
let signal_counter = peripherals.pcnt0;
|
||||
|
||||
signal_counter.set_low_limit(Some(0))?;
|
||||
signal_counter.set_high_limit(Some(i16::MAX))?;
|
||||
|
||||
let ch0 = &signal_counter.channel0;
|
||||
let edge_pin = Input::new(peripherals.gpio22, InputConfig::default());
|
||||
ch0.set_edge_signal(edge_pin.peripheral_input());
|
||||
ch0.set_input_mode(Hold, Increment);
|
||||
ch0.set_ctrl_mode(Keep, Keep);
|
||||
signal_counter.listen();
|
||||
|
||||
for pin in 0..8 {
|
||||
let _ = sensor_expander.pin_into_output(GPIOBank::Bank0, pin);
|
||||
@@ -210,7 +198,7 @@ pub(crate) async fn create_v4(
|
||||
}
|
||||
|
||||
SensorImpl::PulseCounter {
|
||||
// signal_counter,
|
||||
signal_counter,
|
||||
sensor_expander,
|
||||
}
|
||||
}
|
||||
@@ -305,7 +293,6 @@ pub(crate) async fn create_v4(
|
||||
tank_sensor,
|
||||
light,
|
||||
general_fault,
|
||||
//pump_ina,
|
||||
pump_expander,
|
||||
config,
|
||||
battery_monitor,
|
||||
@@ -340,14 +327,24 @@ impl<'a> BoardInteraction<'a> for V4<'a> {
|
||||
&mut self.rtc_module
|
||||
}
|
||||
|
||||
fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError> {
|
||||
async fn get_time(&mut self) -> DateTime<Utc> {
|
||||
self.esp.get_time()
|
||||
}
|
||||
|
||||
async fn set_time(&mut self, time: &DateTime<FixedOffset>) -> FatResult<()> {
|
||||
self.rtc_module.set_rtc_time(&time.to_utc()).await?;
|
||||
self.esp.set_time(time.to_utc());
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError> {
|
||||
self.charger.set_charge_indicator(charging)
|
||||
}
|
||||
|
||||
async fn deep_sleep(&mut self, duration_in_ms: u64) -> ! {
|
||||
async fn deep_sleep_ms(&mut self, duration_in_ms: u64) -> ! {
|
||||
self.awake.set_low();
|
||||
//self.charger.power_save();
|
||||
self.esp.deep_sleep(duration_in_ms).await;
|
||||
self.charger.power_save();
|
||||
self.esp.deep_sleep_ms(duration_in_ms);
|
||||
}
|
||||
|
||||
fn is_day(&self) -> bool {
|
||||
@@ -355,10 +352,10 @@ impl<'a> BoardInteraction<'a> for V4<'a> {
|
||||
}
|
||||
|
||||
async fn light(&mut self, enable: bool) -> Result<(), FatError> {
|
||||
// unsafe { gpio_hold_dis(self.light.pin()) };
|
||||
self.light.set_level(enable.into());
|
||||
// unsafe { gpio_hold_en(self.light.pin()) };
|
||||
Ok(())
|
||||
hold_disable(10);
|
||||
self.light.set_level(enable.into());
|
||||
hold_enable(10);
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn pump(&mut self, plant: usize, enable: bool) -> FatResult<()> {
|
||||
@@ -412,17 +409,17 @@ impl<'a> BoardInteraction<'a> for V4<'a> {
|
||||
}
|
||||
|
||||
async fn general_fault(&mut self, enable: bool) {
|
||||
//FIXME unsafe { gpio_hold_dis(self.general_fault.pin()) };
|
||||
hold_disable(23);
|
||||
self.general_fault.set_level(enable.into());
|
||||
//FIXME unsafe { gpio_hold_en(self.general_fault.pin()) };
|
||||
hold_enable(23);
|
||||
}
|
||||
|
||||
async fn test(&mut self) -> Result<(), FatError> {
|
||||
self.general_fault(true).await;
|
||||
self.general_fault(true).await;
|
||||
Timer::after_millis(100).await;
|
||||
self.general_fault(false).await;
|
||||
self.general_fault(false).await;
|
||||
Timer::after_millis(500).await;
|
||||
self.light(true).await?;
|
||||
self.light(true).await?;
|
||||
Timer::after_millis(500).await;
|
||||
self.light(false).await?;
|
||||
Timer::after_millis(500).await;
|
||||
@@ -432,25 +429,29 @@ impl<'a> BoardInteraction<'a> for V4<'a> {
|
||||
self.fault(i, false).await?;
|
||||
Timer::after_millis(500).await;
|
||||
}
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.pump(i, true).await?;
|
||||
Timer::after_millis(100).await;
|
||||
self.pump(i, false).await?;
|
||||
Timer::after_millis(100).await;
|
||||
}
|
||||
for plant in 0..PLANT_COUNT {
|
||||
let a = self.measure_moisture_hz(plant, Sensor::A).await;
|
||||
let b = self.measure_moisture_hz(plant, Sensor::B).await;
|
||||
let aa = match a {
|
||||
Ok(a) => a as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
let bb = match b {
|
||||
Ok(b) => b as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
LOG_ACCESS.lock().await.log(LogMessage::TestSensor, aa, bb, &plant.to_string(), "").await;
|
||||
}
|
||||
for i in 0..PLANT_COUNT {
|
||||
self.pump(i, true).await?;
|
||||
Timer::after_millis(100).await;
|
||||
self.pump(i, false).await?;
|
||||
Timer::after_millis(100).await;
|
||||
}
|
||||
for plant in 0..PLANT_COUNT {
|
||||
let a = self.measure_moisture_hz(plant, Sensor::A).await;
|
||||
let b = self.measure_moisture_hz(plant, Sensor::B).await;
|
||||
let aa = match a {
|
||||
Ok(a) => a as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
let bb = match b {
|
||||
Ok(b) => b as u32,
|
||||
Err(_) => u32::MAX,
|
||||
};
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(LogMessage::TestSensor, aa, bb, &plant.to_string(), "")
|
||||
.await;
|
||||
}
|
||||
Timer::after_millis(10).await;
|
||||
Ok(())
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::Box;
|
||||
use crate::hal::Sensor;
|
||||
use crate::log::{LogMessage, LOG_ACCESS};
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use alloc::format;
|
||||
use alloc::string::ToString;
|
||||
use async_trait::async_trait;
|
||||
@@ -9,6 +9,7 @@ use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_time::Timer;
|
||||
use esp_hal::i2c::master::I2c;
|
||||
use esp_hal::pcnt::unit::Unit;
|
||||
use esp_hal::twai::Twai;
|
||||
use esp_hal::Blocking;
|
||||
use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface};
|
||||
@@ -29,7 +30,7 @@ const SENSOR_ON: u8 = 5_u8;
|
||||
|
||||
pub enum SensorImpl {
|
||||
PulseCounter {
|
||||
//signal_counter: PcntDriver<'a>,
|
||||
signal_counter: Unit<'static, 0>,
|
||||
sensor_expander:
|
||||
Pca9535Immediate<I2cDevice<'static, CriticalSectionRawMutex, I2c<'static, Blocking>>>,
|
||||
},
|
||||
@@ -43,14 +44,14 @@ impl SensorInteraction for SensorImpl {
|
||||
async fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> FatResult<f32> {
|
||||
match self {
|
||||
SensorImpl::PulseCounter {
|
||||
//signal_counter,
|
||||
signal_counter,
|
||||
sensor_expander,
|
||||
..
|
||||
} => {
|
||||
let mut results = [0_f32; REPEAT_MOIST_MEASURE];
|
||||
for repeat in 0..REPEAT_MOIST_MEASURE {
|
||||
//signal_counter.counter_pause()?;
|
||||
//signal_counter.counter_clear()?;
|
||||
signal_counter.pause();
|
||||
signal_counter.clear();
|
||||
|
||||
//Disable all
|
||||
sensor_expander.pin_set_high(GPIOBank::Bank0, MS4)?;
|
||||
@@ -90,9 +91,9 @@ impl SensorInteraction for SensorImpl {
|
||||
|
||||
//give some time to stabilize
|
||||
Timer::after_millis(10).await;
|
||||
//signal_counter.counter_resume()?;
|
||||
signal_counter.resume();
|
||||
Timer::after_millis(measurement).await;
|
||||
//signal_counter.counter_pause()?;
|
||||
signal_counter.pause();
|
||||
sensor_expander.pin_set_high(GPIOBank::Bank0, MS4)?;
|
||||
sensor_expander.pin_set_low(GPIOBank::Bank0, SENSOR_ON)?;
|
||||
sensor_expander.pin_set_low(GPIOBank::Bank0, MS0)?;
|
||||
@@ -121,9 +122,9 @@ impl SensorInteraction for SensorImpl {
|
||||
let median = results[mid];
|
||||
Ok(median)
|
||||
}
|
||||
SensorImpl::CanBus { twai } => {
|
||||
Err(FatError::String {error: "Not yet implemented".to_string()})
|
||||
}
|
||||
SensorImpl::CanBus { twai } => Err(FatError::String {
|
||||
error: "Not yet implemented".to_string(),
|
||||
}),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,24 +1,26 @@
|
||||
use crate::bail;
|
||||
use crate::hal::{ADC1, TANK_MULTI_SAMPLE};
|
||||
use crate::fat_error::FatError;
|
||||
use crate::hal::{ADC1, TANK_MULTI_SAMPLE};
|
||||
use embassy_time::Timer;
|
||||
use esp_hal::analog::adc::{Adc, AdcConfig, AdcPin, Attenuation};
|
||||
use esp_hal::analog::adc::{Adc, AdcCalLine, AdcConfig, AdcPin, Attenuation};
|
||||
use esp_hal::delay::Delay;
|
||||
use esp_hal::gpio::{Flex, Input, Output, OutputConfig, Pull};
|
||||
use esp_hal::gpio::{DriveMode, Flex, Input, InputConfig, Output, OutputConfig, Pull};
|
||||
use esp_hal::pcnt::channel::CtrlMode::Keep;
|
||||
use esp_hal::pcnt::channel::EdgeMode::{Hold, Increment};
|
||||
use esp_hal::pcnt::unit::Unit;
|
||||
use esp_hal::peripherals::GPIO5;
|
||||
use esp_hal::Blocking;
|
||||
use esp_hal::Async;
|
||||
use esp_println::println;
|
||||
use littlefs2::object_safe::DynStorage;
|
||||
use onewire::{ds18b20, Device, DeviceSearch, OneWire, DS18B20};
|
||||
|
||||
unsafe impl Send for TankSensor<'_> {}
|
||||
|
||||
pub struct TankSensor<'a> {
|
||||
one_wire_bus: OneWire<Flex<'a>>,
|
||||
tank_channel: Adc<'a, ADC1<'a>, Blocking>,
|
||||
tank_channel: Adc<'a, ADC1<'a>, Async>,
|
||||
tank_power: Output<'a>,
|
||||
tank_pin: AdcPin<GPIO5<'a>, ADC1<'a>>,
|
||||
// flow_counter: PcntDriver<'a>,
|
||||
// delay: Delay,
|
||||
tank_pin: AdcPin<GPIO5<'a>, ADC1<'a>, AdcCalLine<ADC1<'a>>>,
|
||||
flow_counter: Unit<'a, 1>,
|
||||
}
|
||||
|
||||
impl<'a> TankSensor<'a> {
|
||||
@@ -30,62 +32,55 @@ impl<'a> TankSensor<'a> {
|
||||
flow_sensor: Input,
|
||||
pcnt1: Unit<'a, 1>,
|
||||
) -> Result<TankSensor<'a>, FatError> {
|
||||
one_wire_pin.apply_output_config(&OutputConfig::default().with_pull(Pull::None));
|
||||
one_wire_pin.apply_output_config(
|
||||
&OutputConfig::default()
|
||||
.with_drive_mode(DriveMode::OpenDrain)
|
||||
.with_pull(Pull::None),
|
||||
);
|
||||
one_wire_pin.apply_input_config(&InputConfig::default().with_pull(Pull::None));
|
||||
one_wire_pin.set_high();
|
||||
one_wire_pin.set_input_enable(true);
|
||||
one_wire_pin.set_output_enable(true);
|
||||
|
||||
let mut adc1_config = AdcConfig::new();
|
||||
let tank_pin = adc1_config.enable_pin(gpio5, Attenuation::_11dB);
|
||||
let mut tank_channel = Adc::new(adc1, adc1_config);
|
||||
let tank_pin =
|
||||
adc1_config.enable_pin_with_cal::<_, AdcCalLine<_>>(gpio5, Attenuation::_11dB);
|
||||
let tank_channel = Adc::new(adc1, adc1_config).into_async();
|
||||
|
||||
let one_wire_bus = OneWire::new(one_wire_pin, false);
|
||||
|
||||
//
|
||||
// let mut flow_counter = PcntDriver::new(
|
||||
// pcnt1,
|
||||
// Some(flow_sensor_pin),
|
||||
// Option::<AnyInputPin>::None,
|
||||
// Option::<AnyInputPin>::None,
|
||||
// Option::<AnyInputPin>::None,
|
||||
// )?;
|
||||
//
|
||||
// flow_counter.channel_config(
|
||||
// PcntChannel::Channel1,
|
||||
// PinIndex::Pin0,
|
||||
// PinIndex::Pin1,
|
||||
// &PcntChannelConfig {
|
||||
// lctrl_mode: PcntControlMode::Keep,
|
||||
// hctrl_mode: PcntControlMode::Keep,
|
||||
// pos_mode: PcntCountMode::Increment,
|
||||
// neg_mode: PcntCountMode::Hold,
|
||||
// counter_h_lim: i16::MAX,
|
||||
// counter_l_lim: 0,
|
||||
// },
|
||||
// )?;
|
||||
//
|
||||
pcnt1.set_high_limit(Some(i16::MAX))?;
|
||||
|
||||
let ch0 = &pcnt1.channel0;
|
||||
ch0.set_edge_signal(flow_sensor.peripheral_input());
|
||||
ch0.set_input_mode(Hold, Increment);
|
||||
ch0.set_ctrl_mode(Keep, Keep);
|
||||
pcnt1.listen();
|
||||
|
||||
Ok(TankSensor {
|
||||
one_wire_bus,
|
||||
tank_channel,
|
||||
tank_power,
|
||||
tank_pin, // flow_counter,
|
||||
// delay: Default::default(),
|
||||
tank_pin,
|
||||
flow_counter: pcnt1,
|
||||
})
|
||||
}
|
||||
|
||||
pub fn reset_flow_meter(&mut self) {
|
||||
// self.flow_counter.counter_pause().unwrap();
|
||||
// self.flow_counter.counter_clear().unwrap();
|
||||
self.flow_counter.pause();
|
||||
self.flow_counter.clear();
|
||||
}
|
||||
|
||||
pub fn start_flow_meter(&mut self) {
|
||||
//self.flow_counter.counter_resume().unwrap();
|
||||
self.flow_counter.resume();
|
||||
}
|
||||
|
||||
pub fn get_flow_meter_value(&mut self) -> i16 {
|
||||
//self.flow_counter.get_counter_value().unwrap()
|
||||
5_i16
|
||||
self.flow_counter.value()
|
||||
}
|
||||
|
||||
pub fn stop_flow_meter(&mut self) -> i16 {
|
||||
//self.flow_counter.counter_pause().unwrap();
|
||||
self.flow_counter.pause();
|
||||
self.get_flow_meter_value()
|
||||
}
|
||||
|
||||
@@ -93,15 +88,33 @@ impl<'a> TankSensor<'a> {
|
||||
//multisample should be moved to water_temperature_c
|
||||
let mut attempt = 1;
|
||||
let mut delay = Delay::new();
|
||||
self.one_wire_bus.reset(&mut delay)?;
|
||||
|
||||
let presence = self.one_wire_bus.reset(&mut delay)?;
|
||||
println!("OneWire: reset presence pulse = {}", presence);
|
||||
if !presence {
|
||||
println!("OneWire: no device responded to reset — check pull-up resistor and wiring");
|
||||
}
|
||||
|
||||
let mut search = DeviceSearch::new();
|
||||
let mut water_temp_sensor: Option<Device> = None;
|
||||
let mut devices_found = 0u8;
|
||||
while let Some(device) = self.one_wire_bus.search_next(&mut search, &mut delay)? {
|
||||
devices_found += 1;
|
||||
println!(
|
||||
"OneWire: found device #{} family=0x{:02X} addr={:02X?}",
|
||||
devices_found, device.address[0], device.address
|
||||
);
|
||||
if device.address[0] == ds18b20::FAMILY_CODE {
|
||||
water_temp_sensor = Some(device);
|
||||
break;
|
||||
} else {
|
||||
println!("OneWire: skipping device — not a DS18B20 (family 0x{:02X} != 0x{:02X})", device.address[0], ds18b20::FAMILY_CODE);
|
||||
}
|
||||
}
|
||||
if devices_found == 0 {
|
||||
println!("OneWire: search found zero devices on the bus");
|
||||
}
|
||||
|
||||
match water_temp_sensor {
|
||||
Some(device) => {
|
||||
println!("Found one wire device: {:?}", device);
|
||||
@@ -153,19 +166,15 @@ impl<'a> TankSensor<'a> {
|
||||
Timer::after_millis(100).await;
|
||||
|
||||
let mut store = [0_u16; TANK_MULTI_SAMPLE];
|
||||
for multisample in 0..TANK_MULTI_SAMPLE {
|
||||
let mut asy = (&mut self.tank_channel);
|
||||
|
||||
let value = asy.read_oneshot(&mut self.tank_pin);
|
||||
//force yield
|
||||
for sample in store.iter_mut() {
|
||||
*sample = self.tank_channel.read_oneshot(&mut self.tank_pin).await;
|
||||
//force yield between successful samples
|
||||
Timer::after_millis(10).await;
|
||||
store[multisample] = value.unwrap();
|
||||
}
|
||||
self.tank_power.set_low();
|
||||
|
||||
store.sort();
|
||||
//TODO probably wrong? check!
|
||||
let median_mv = store[6] as f32 * 3300_f32 / 4096_f32;
|
||||
Ok(median_mv)
|
||||
let median_mv = store[TANK_MULTI_SAMPLE / 2] as f32;
|
||||
Ok(median_mv / 1000.0)
|
||||
}
|
||||
}
|
||||
|
||||
108
rust/src/log/interceptor.rs
Normal file
108
rust/src/log/interceptor.rs
Normal file
@@ -0,0 +1,108 @@
|
||||
use alloc::string::String;
|
||||
use alloc::vec::Vec;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::blocking_mutex::Mutex as BlockingMutex;
|
||||
use log::{LevelFilter, Log, Metadata, Record};
|
||||
|
||||
const MAX_LIVE_LOG_ENTRIES: usize = 64;
|
||||
|
||||
struct LiveLogBuffer {
|
||||
entries: Vec<(u64, String)>,
|
||||
next_seq: u64,
|
||||
}
|
||||
|
||||
impl LiveLogBuffer {
|
||||
const fn new() -> Self {
|
||||
Self {
|
||||
entries: Vec::new(),
|
||||
next_seq: 0,
|
||||
}
|
||||
}
|
||||
|
||||
fn push(&mut self, text: String) {
|
||||
if self.entries.len() >= MAX_LIVE_LOG_ENTRIES {
|
||||
self.entries.remove(0);
|
||||
}
|
||||
self.entries.push((self.next_seq, text));
|
||||
self.next_seq += 1;
|
||||
}
|
||||
|
||||
fn get_after(&self, after: Option<u64>) -> (Vec<(u64, String)>, bool, u64) {
|
||||
let next_seq = self.next_seq;
|
||||
match after {
|
||||
None => (self.entries.clone(), false, next_seq),
|
||||
Some(after_seq) => {
|
||||
let result: Vec<_> = self.entries
|
||||
.iter()
|
||||
.filter(|(seq, _)| *seq > after_seq)
|
||||
.cloned()
|
||||
.collect();
|
||||
|
||||
// Dropped if there are entries that should exist (seq > after_seq) but
|
||||
// the oldest retained entry has a higher seq than after_seq + 1.
|
||||
let dropped = if next_seq > after_seq.saturating_add(1) {
|
||||
if let Some((oldest_seq, _)) = self.entries.first() {
|
||||
*oldest_seq > after_seq.saturating_add(1)
|
||||
} else {
|
||||
// Buffer empty but entries were written — all dropped
|
||||
true
|
||||
}
|
||||
} else {
|
||||
false
|
||||
};
|
||||
|
||||
(result, dropped, next_seq)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
pub struct InterceptorLogger {
|
||||
live_log: BlockingMutex<CriticalSectionRawMutex, core::cell::RefCell<LiveLogBuffer>>,
|
||||
}
|
||||
|
||||
impl InterceptorLogger {
|
||||
pub const fn new() -> Self {
|
||||
Self {
|
||||
live_log: BlockingMutex::new(core::cell::RefCell::new(LiveLogBuffer::new())),
|
||||
}
|
||||
}
|
||||
|
||||
/// Returns (entries_after, dropped, next_seq).
|
||||
/// Pass `after = None` to retrieve the entire current buffer.
|
||||
/// Pass `after = Some(seq)` to retrieve only entries with seq > that value.
|
||||
pub fn get_live_logs(&self, after: Option<u64>) -> (Vec<(u64, String)>, bool, u64) {
|
||||
self.live_log.lock(|buf| buf.borrow().get_after(after))
|
||||
}
|
||||
|
||||
pub fn init(&'static self) {
|
||||
match log::set_logger(self).map(|()| log::set_max_level(LevelFilter::Info)) {
|
||||
Ok(()) => {}
|
||||
Err(_e) => {
|
||||
esp_println::println!("ERROR: Logger already set");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl Log for InterceptorLogger {
|
||||
fn enabled(&self, metadata: &Metadata) -> bool {
|
||||
metadata.level() <= log::Level::Info
|
||||
}
|
||||
|
||||
fn log(&self, record: &Record) {
|
||||
if self.enabled(record.metadata()) {
|
||||
let message = alloc::format!("{}: {}", record.level(), record.args());
|
||||
|
||||
// Print to serial
|
||||
esp_println::println!("{}", message);
|
||||
|
||||
// Store in live log ring buffer
|
||||
self.live_log.lock(|buf| {
|
||||
buf.borrow_mut().push(message);
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
fn flush(&self) {}
|
||||
}
|
||||
@@ -1,20 +1,21 @@
|
||||
use crate::hal::TIME_ACCESS;
|
||||
use crate::vec;
|
||||
use crate::BOARD_ACCESS;
|
||||
use alloc::string::ToString;
|
||||
use alloc::vec::Vec;
|
||||
use bytemuck::{AnyBitPattern, Pod, Zeroable};
|
||||
use deranged::RangedU8;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::channel::Channel;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use esp_hal::Persistable;
|
||||
use log::info;
|
||||
use log::{info, warn};
|
||||
use serde::Serialize;
|
||||
use strum_macros::IntoStaticStr;
|
||||
use unit_enum::UnitEnum;
|
||||
|
||||
const LOG_ARRAY_SIZE: u8 = 220;
|
||||
const MAX_LOG_ARRAY_INDEX: u8 = LOG_ARRAY_SIZE - 1;
|
||||
#[esp_hal::ram(rtc_fast, persistent)]
|
||||
#[esp_hal::ram(unstable(rtc_fast), unstable(persistent))]
|
||||
static mut LOG_ARRAY: LogArray = LogArray {
|
||||
buffer: [LogEntryInner {
|
||||
timestamp: 0,
|
||||
@@ -26,8 +27,45 @@ static mut LOG_ARRAY: LogArray = LogArray {
|
||||
}; LOG_ARRAY_SIZE as usize],
|
||||
head: 0,
|
||||
};
|
||||
|
||||
// this is the only reference created for LOG_ARRAY and the only way to access it
|
||||
#[allow(static_mut_refs)]
|
||||
pub static LOG_ACCESS: Mutex<CriticalSectionRawMutex, &'static mut LogArray> =
|
||||
unsafe { Mutex::new(&mut *&raw mut LOG_ARRAY) };
|
||||
unsafe { Mutex::new(&mut LOG_ARRAY) };
|
||||
|
||||
mod interceptor;
|
||||
|
||||
pub use interceptor::InterceptorLogger;
|
||||
|
||||
pub static INTERCEPTOR: InterceptorLogger = InterceptorLogger::new();
|
||||
|
||||
pub struct LogRequest {
|
||||
pub message_key: LogMessage,
|
||||
pub number_a: u32,
|
||||
pub number_b: u32,
|
||||
pub txt_short: heapless::String<TXT_SHORT_LENGTH>,
|
||||
pub txt_long: heapless::String<TXT_LONG_LENGTH>,
|
||||
}
|
||||
|
||||
static LOG_CHANNEL: Channel<CriticalSectionRawMutex, LogRequest, 16> = Channel::new();
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn log_task() {
|
||||
loop {
|
||||
let request = LOG_CHANNEL.receive().await;
|
||||
LOG_ACCESS
|
||||
.lock()
|
||||
.await
|
||||
.log(
|
||||
request.message_key,
|
||||
request.number_a,
|
||||
request.number_b,
|
||||
request.txt_short.as_str(),
|
||||
request.txt_long.as_str(),
|
||||
)
|
||||
.await;
|
||||
}
|
||||
}
|
||||
|
||||
const TXT_SHORT_LENGTH: usize = 8;
|
||||
const TXT_LONG_LENGTH: usize = 32;
|
||||
@@ -77,10 +115,31 @@ impl From<LogEntryInner> for LogEntry {
|
||||
}
|
||||
}
|
||||
|
||||
pub fn log(message_key: LogMessage, number_a: u32, number_b: u32, txt_short: &str, txt_long: &str) {
|
||||
let mut txt_short_stack: heapless::String<TXT_SHORT_LENGTH> = heapless::String::new();
|
||||
let mut txt_long_stack: heapless::String<TXT_LONG_LENGTH> = heapless::String::new();
|
||||
|
||||
limit_length(txt_short, &mut txt_short_stack);
|
||||
limit_length(txt_long, &mut txt_long_stack);
|
||||
|
||||
match LOG_CHANNEL.try_send(LogRequest {
|
||||
message_key,
|
||||
number_a,
|
||||
number_b,
|
||||
txt_short: txt_short_stack,
|
||||
txt_long: txt_long_stack,
|
||||
}) {
|
||||
Ok(_) => {}
|
||||
Err(_) => {
|
||||
warn!("Log channel full, dropping log entry");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl LogArray {
|
||||
pub fn get(&mut self) -> Vec<LogEntry> {
|
||||
let head: RangedU8<0, MAX_LOG_ARRAY_INDEX> =
|
||||
RangedU8::new(self.head).unwrap_or(RangedU8::new(0).unwrap());
|
||||
RangedU8::new(self.head).unwrap_or(RangedU8::new_saturating(0));
|
||||
|
||||
let mut rv: Vec<LogEntry> = Vec::new();
|
||||
let mut index = head.wrapping_sub(1);
|
||||
@@ -103,15 +162,12 @@ impl LogArray {
|
||||
txt_long: &str,
|
||||
) {
|
||||
let mut head: RangedU8<0, MAX_LOG_ARRAY_INDEX> =
|
||||
RangedU8::new(self.head).unwrap_or(RangedU8::new(0).unwrap());
|
||||
RangedU8::new(self.head).unwrap_or(RangedU8::new_saturating(0));
|
||||
|
||||
let mut txt_short_stack: heapless::String<TXT_SHORT_LENGTH> = heapless::String::new();
|
||||
let mut txt_long_stack: heapless::String<TXT_LONG_LENGTH> = heapless::String::new();
|
||||
|
||||
limit_length(txt_short, &mut txt_short_stack);
|
||||
limit_length(txt_long, &mut txt_long_stack);
|
||||
|
||||
let time = TIME_ACCESS.get().await.current_time_us() / 1000;
|
||||
let time = {
|
||||
let mut guard = BOARD_ACCESS.get().await.lock().await;
|
||||
guard.board_hal.get_esp().rtc.current_time_us()
|
||||
} / 1000;
|
||||
|
||||
let ordinal = message_key.ordinal() as u16;
|
||||
let template: &str = message_key.into();
|
||||
@@ -121,19 +177,15 @@ impl LogArray {
|
||||
template_string = template_string.replace("${txt_long}", txt_long);
|
||||
template_string = template_string.replace("${txt_short}", txt_short);
|
||||
|
||||
info!("{}", template_string);
|
||||
info!("{template_string}");
|
||||
|
||||
let to_modify = &mut self.buffer[head.get() as usize];
|
||||
to_modify.timestamp = time;
|
||||
to_modify.message_id = ordinal;
|
||||
to_modify.a = number_a;
|
||||
to_modify.b = number_b;
|
||||
to_modify
|
||||
.txt_short
|
||||
.clone_from_slice(&txt_short_stack.as_bytes());
|
||||
to_modify
|
||||
.txt_long
|
||||
.clone_from_slice(&txt_long_stack.as_bytes());
|
||||
to_modify.txt_short.clone_from_slice(txt_short.as_bytes());
|
||||
to_modify.txt_long.clone_from_slice(txt_long.as_bytes());
|
||||
head = head.wrapping_add(1);
|
||||
self.head = head.get();
|
||||
}
|
||||
@@ -145,18 +197,37 @@ fn limit_length<const LIMIT: usize>(input: &str, target: &mut heapless::String<L
|
||||
Ok(_) => {} //continue adding chars
|
||||
Err(_) => {
|
||||
//clear space for two asci chars
|
||||
info!("pushing char {char} to limit {LIMIT} current value {target} input {input}");
|
||||
while target.len() + 2 >= LIMIT {
|
||||
target.pop().unwrap();
|
||||
target.pop();
|
||||
}
|
||||
//add .. to shortened strings
|
||||
target.push('.').unwrap();
|
||||
target.push('.').unwrap();
|
||||
return;
|
||||
match target.push('.') {
|
||||
Ok(_) => {}
|
||||
Err(_) => {
|
||||
warn!(
|
||||
"Error pushin . to limit {LIMIT} current value {target} input {input}"
|
||||
)
|
||||
}
|
||||
}
|
||||
match target.push('.') {
|
||||
Ok(_) => {}
|
||||
Err(_) => {
|
||||
warn!(
|
||||
"Error pushin . to limit {LIMIT} current value {target} input {input}"
|
||||
)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
while target.len() < LIMIT {
|
||||
target.push(' ').unwrap();
|
||||
match target.push(' ') {
|
||||
Ok(_) => {}
|
||||
Err(_) => {
|
||||
warn!("Error pushing space to limit {LIMIT} current value {target} input {input}")
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -196,7 +267,7 @@ pub enum LogMessage {
|
||||
StayAlive,
|
||||
#[strum(serialize = "Connecting mqtt ${txt_short} with id ${txt_long}")]
|
||||
MqttInfo,
|
||||
#[strum(serialize = "Received stay alive with value ${txt_short}")]
|
||||
#[strum(serialize = "Received stay alive with value ${number_a}")]
|
||||
MqttStayAliveRec,
|
||||
#[strum(serialize = "Unknown topic recieved ${txt_long}")]
|
||||
UnknownTopic,
|
||||
@@ -240,6 +311,20 @@ pub enum LogMessage {
|
||||
PumpOpenLoopCurrent,
|
||||
#[strum(serialize = "Pump Open current sensor required but did not work: ${number_a}")]
|
||||
PumpMissingSensorCurrent,
|
||||
#[strum(
|
||||
serialize = "Fertilizer applied for ${number_a}s on plant ${number_b} (last application ${txt_short} minutes ago)"
|
||||
)]
|
||||
FertilizerApplied,
|
||||
#[strum(serialize = "MPPT Current sensor could not be reached")]
|
||||
MPPTError,
|
||||
#[strum(
|
||||
serialize = "Trace: a: ${number_a} b: ${number_b} txt_s ${txt_short} long ${txt_long}"
|
||||
)]
|
||||
Trace,
|
||||
#[strum(serialize = "Parsing error reading message")]
|
||||
UnknownMessage,
|
||||
#[strum(serialize = "Going to deep sleep for ${number_a} minutes")]
|
||||
DeepSleep,
|
||||
}
|
||||
|
||||
#[derive(Serialize)]
|
||||
@@ -258,9 +343,9 @@ impl From<&LogMessage> for MessageTranslation {
|
||||
}
|
||||
|
||||
impl LogMessage {
|
||||
pub fn to_log_localisation_config() -> Vec<MessageTranslation> {
|
||||
pub fn log_localisation_config() -> Vec<MessageTranslation> {
|
||||
Vec::from_iter((0..LogMessage::len()).map(|i| {
|
||||
let msg_type = LogMessage::from_ordinal(i).unwrap();
|
||||
let msg_type = LogMessage::from_ordinal(i).unwrap_or(LogMessage::UnknownMessage);
|
||||
(&msg_type).into()
|
||||
}))
|
||||
}
|
||||
|
||||
875
rust/src/main.rs
875
rust/src/main.rs
File diff suppressed because it is too large
Load Diff
34
rust/src/mcutie_3_0_0/Cargo.toml
Normal file
34
rust/src/mcutie_3_0_0/Cargo.toml
Normal file
@@ -0,0 +1,34 @@
|
||||
[package]
|
||||
name = "mcutie"
|
||||
version = "3.0.0"
|
||||
edition = "2021"
|
||||
|
||||
[lib]
|
||||
path = "lib.rs"
|
||||
|
||||
[features]
|
||||
default = []
|
||||
homeassistant = []
|
||||
serde = ["dep:serde", "heapless/serde"]
|
||||
defmt = []
|
||||
log = ["dep:log"]
|
||||
|
||||
[dependencies]
|
||||
embassy-net = { version = "0.8.0", default-features = false, features = ["tcp", "dns", "proto-ipv4", "proto-ipv6", "medium-ethernet"] }
|
||||
embassy-sync = { version = "0.8.0", default-features = false }
|
||||
embassy-time = { version = "0.5.1", default-features = false }
|
||||
embassy-futures = { version = "0.1.2", default-features = false }
|
||||
embedded-io = { version = "0.7.1", default-features = false }
|
||||
embedded-io-async = { version = "0.7.0", default-features = false }
|
||||
heapless = { version = "0.7.17", default-features = false }
|
||||
mqttrs = { version = "0.4.1", default-features = false }
|
||||
once_cell = { version = "1.21.3", default-features = false, features = ["critical-section"] }
|
||||
pin-project = { version = "1.1.10", default-features = false }
|
||||
hex = { version = "0.4.3", default-features = false }
|
||||
serde = { version = "1.0.228", default-features = false, features = ["derive"], optional = true }
|
||||
log = { version = "0.4.28", default-features = false, optional = true }
|
||||
|
||||
[dev-dependencies]
|
||||
futures-executor = "0.3.31"
|
||||
futures-timer = "3.0.3"
|
||||
futures-util = "0.3.31"
|
||||
124
rust/src/mcutie_3_0_0/buffer.rs
Normal file
124
rust/src/mcutie_3_0_0/buffer.rs
Normal file
@@ -0,0 +1,124 @@
|
||||
use core::{cmp, fmt, ops::Deref};
|
||||
|
||||
use embedded_io::{SliceWriteError, Write};
|
||||
use mqttrs::{encode_slice, Packet};
|
||||
|
||||
use crate::Error;
|
||||
|
||||
/// A stack allocated buffer that can be written to and then read back from.
|
||||
/// Dereferencing as a [`u8`] slice allows access to previously written data.
|
||||
///
|
||||
/// Can be written to with [`write!`] and supports [`embedded_io::Write`] and
|
||||
/// [`embedded_io_async::Write`].
|
||||
pub struct Buffer<const N: usize> {
|
||||
bytes: [u8; N],
|
||||
cursor: usize,
|
||||
}
|
||||
|
||||
impl<const N: usize> Default for Buffer<N> {
|
||||
fn default() -> Self {
|
||||
Self::new()
|
||||
}
|
||||
}
|
||||
|
||||
impl<const N: usize> Buffer<N> {
|
||||
/// Creates a new buffer.
|
||||
pub(crate) const fn new() -> Self {
|
||||
Self {
|
||||
bytes: [0; N],
|
||||
cursor: 0,
|
||||
}
|
||||
}
|
||||
|
||||
/// Creates a new buffer and writes the given data into it.
|
||||
pub(crate) fn from(buf: &[u8]) -> Result<Self, Error> {
|
||||
let mut buffer = Self::new();
|
||||
match buffer.write_all(buf) {
|
||||
Ok(()) => Ok(buffer),
|
||||
Err(_) => Err(Error::TooLarge),
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) fn encode_packet(&mut self, packet: &Packet<'_>) -> Result<(), mqttrs::Error> {
|
||||
let len = encode_slice(packet, &mut self.bytes[self.cursor..])?;
|
||||
self.cursor += len;
|
||||
|
||||
Ok(())
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
/// Serializes a value into this buffer using JSON.
|
||||
pub(crate) fn serialize_json<T: serde::Serialize>(
|
||||
&mut self,
|
||||
value: &T,
|
||||
) -> Result<(), serde_json_core::ser::Error> {
|
||||
let len = serde_json_core::to_slice(value, &mut self.bytes[self.cursor..])?;
|
||||
self.cursor += len;
|
||||
|
||||
Ok(())
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
/// Deserializes this buffer using JSON into the given type.
|
||||
pub fn deserialize_json<'a, T: serde::Deserialize<'a>>(
|
||||
&'a self,
|
||||
) -> Result<T, serde_json_core::de::Error> {
|
||||
let (result, _) = serde_json_core::from_slice(self)?;
|
||||
|
||||
Ok(result)
|
||||
}
|
||||
|
||||
/// The number of bytes available for writing into this buffer.
|
||||
pub fn available(&self) -> usize {
|
||||
N - self.cursor
|
||||
}
|
||||
}
|
||||
|
||||
impl<const N: usize> Deref for Buffer<N> {
|
||||
type Target = [u8];
|
||||
|
||||
fn deref(&self) -> &Self::Target {
|
||||
&self.bytes[0..self.cursor]
|
||||
}
|
||||
}
|
||||
|
||||
impl<const N: usize> fmt::Write for Buffer<N> {
|
||||
fn write_str(&mut self, s: &str) -> fmt::Result {
|
||||
self.write_all(s.as_bytes()).map_err(|_| fmt::Error)
|
||||
}
|
||||
}
|
||||
|
||||
impl<const N: usize> embedded_io::ErrorType for Buffer<N> {
|
||||
type Error = SliceWriteError;
|
||||
}
|
||||
|
||||
impl<const N: usize> embedded_io::Write for Buffer<N> {
|
||||
fn write(&mut self, buf: &[u8]) -> Result<usize, Self::Error> {
|
||||
if buf.is_empty() {
|
||||
return Ok(0);
|
||||
}
|
||||
|
||||
let writable = cmp::min(self.available(), buf.len());
|
||||
if writable == 0 {
|
||||
Err(SliceWriteError::Full)
|
||||
} else {
|
||||
self.bytes[self.cursor..self.cursor + writable].copy_from_slice(buf);
|
||||
self.cursor += writable;
|
||||
Ok(writable)
|
||||
}
|
||||
}
|
||||
|
||||
fn flush(&mut self) -> Result<(), Self::Error> {
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
|
||||
impl<const N: usize> embedded_io_async::Write for Buffer<N> {
|
||||
async fn write(&mut self, buf: &[u8]) -> Result<usize, Self::Error> {
|
||||
<Self as embedded_io::Write>::write(self, buf)
|
||||
}
|
||||
|
||||
async fn flush(&mut self) -> Result<(), Self::Error> {
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
80
rust/src/mcutie_3_0_0/fmt.rs
Normal file
80
rust/src/mcutie_3_0_0/fmt.rs
Normal file
@@ -0,0 +1,80 @@
|
||||
#![macro_use]
|
||||
|
||||
#[cfg(all(feature = "defmt", feature = "log"))]
|
||||
compile_error!("The `defmt` and `log` features cannot both be enabled at the same time.");
|
||||
|
||||
#[cfg(not(feature = "defmt"))]
|
||||
use core::fmt;
|
||||
|
||||
#[cfg(feature = "defmt")]
|
||||
pub(crate) use ::defmt::Debug2Format;
|
||||
|
||||
#[cfg(not(feature = "defmt"))]
|
||||
pub(crate) struct Debug2Format<D: fmt::Debug>(pub(crate) D);
|
||||
|
||||
#[cfg(feature = "log")]
|
||||
impl<D: fmt::Debug> fmt::Debug for Debug2Format<D> {
|
||||
fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
|
||||
self.0.fmt(f)
|
||||
}
|
||||
}
|
||||
|
||||
#[collapse_debuginfo(yes)]
|
||||
macro_rules! trace {
|
||||
($s:literal $(, $x:expr)* $(,)?) => {
|
||||
#[cfg(feature = "defmt")]
|
||||
::defmt::trace!($s $(, $x)*);
|
||||
#[cfg(feature = "log")]
|
||||
::log::trace!($s $(, $x)*);
|
||||
#[cfg(not(any(feature="defmt", feature="log")))]
|
||||
let _ = ($( & $x ),*);
|
||||
};
|
||||
}
|
||||
|
||||
#[collapse_debuginfo(yes)]
|
||||
macro_rules! debug {
|
||||
($s:literal $(, $x:expr)* $(,)?) => {
|
||||
#[cfg(feature = "defmt")]
|
||||
::defmt::debug!($s $(, $x)*);
|
||||
#[cfg(feature = "log")]
|
||||
::log::debug!($s $(, $x)*);
|
||||
#[cfg(not(any(feature="defmt", feature="log")))]
|
||||
let _ = ($( & $x ),*);
|
||||
};
|
||||
}
|
||||
|
||||
#[collapse_debuginfo(yes)]
|
||||
macro_rules! info {
|
||||
($s:literal $(, $x:expr)* $(,)?) => {
|
||||
#[cfg(feature = "defmt")]
|
||||
::defmt::info!($s $(, $x)*);
|
||||
#[cfg(feature = "log")]
|
||||
::log::info!($s $(, $x)*);
|
||||
#[cfg(not(any(feature="defmt", feature="log")))]
|
||||
let _ = ($( & $x ),*);
|
||||
};
|
||||
}
|
||||
|
||||
#[collapse_debuginfo(yes)]
|
||||
macro_rules! warn {
|
||||
($s:literal $(, $x:expr)* $(,)?) => {
|
||||
#[cfg(feature = "defmt")]
|
||||
::defmt::warn!($s $(, $x)*);
|
||||
#[cfg(feature = "log")]
|
||||
::log::warn!($s $(, $x)*);
|
||||
#[cfg(not(any(feature="defmt", feature="log")))]
|
||||
let _ = ($( & $x ),*);
|
||||
};
|
||||
}
|
||||
|
||||
#[collapse_debuginfo(yes)]
|
||||
macro_rules! error {
|
||||
($s:literal $(, $x:expr)* $(,)?) => {
|
||||
#[cfg(feature = "defmt")]
|
||||
::defmt::error!($s $(, $x)*);
|
||||
#[cfg(feature = "log")]
|
||||
::log::error!($s $(, $x)*);
|
||||
#[cfg(not(any(feature="defmt", feature="log")))]
|
||||
let _ = ($( & $x ),*);
|
||||
};
|
||||
}
|
||||
120
rust/src/mcutie_3_0_0/homeassistant/binary_sensor.rs
Normal file
120
rust/src/mcutie_3_0_0/homeassistant/binary_sensor.rs
Normal file
@@ -0,0 +1,120 @@
|
||||
//! Tools for publishing a [Home Assistant binary sensor](https://www.home-assistant.io/integrations/binary_sensor.mqtt/).
|
||||
use core::ops::Deref;
|
||||
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
use crate::{homeassistant::Component, Error, Publishable, Topic};
|
||||
|
||||
/// The state of the sensor. Can be easily converted to or from a [`bool`].
|
||||
#[derive(Clone, Copy, PartialEq, Eq, Serialize, Deserialize)]
|
||||
#[serde(from = "&str", into = "&'static str")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum BinarySensorState {
|
||||
On,
|
||||
Off,
|
||||
}
|
||||
|
||||
impl From<BinarySensorState> for &'static str {
|
||||
fn from(state: BinarySensorState) -> Self {
|
||||
match state {
|
||||
BinarySensorState::On => "ON",
|
||||
BinarySensorState::Off => "OFF",
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a> From<&'a str> for BinarySensorState {
|
||||
fn from(st: &'a str) -> Self {
|
||||
if st == "ON" {
|
||||
Self::On
|
||||
} else {
|
||||
Self::Off
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl From<bool> for BinarySensorState {
|
||||
fn from(val: bool) -> Self {
|
||||
if val {
|
||||
BinarySensorState::On
|
||||
} else {
|
||||
BinarySensorState::Off
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl From<BinarySensorState> for bool {
|
||||
fn from(val: BinarySensorState) -> Self {
|
||||
match val {
|
||||
BinarySensorState::On => true,
|
||||
BinarySensorState::Off => true,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl AsRef<[u8]> for BinarySensorState {
|
||||
fn as_ref(&self) -> &'static [u8] {
|
||||
match self {
|
||||
Self::On => "ON".as_bytes(),
|
||||
Self::Off => "OFF".as_bytes(),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// The type of sensor.
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "snake_case")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum BinarySensorClass {
|
||||
Battery,
|
||||
BatteryCharging,
|
||||
CarbonMonoxide,
|
||||
Cold,
|
||||
Connectivity,
|
||||
Door,
|
||||
GarageDoor,
|
||||
Gas,
|
||||
Heat,
|
||||
Light,
|
||||
Lock,
|
||||
Moisture,
|
||||
Motion,
|
||||
Moving,
|
||||
Occupancy,
|
||||
Opening,
|
||||
Plug,
|
||||
Power,
|
||||
Presence,
|
||||
Problem,
|
||||
Running,
|
||||
Safety,
|
||||
Smoke,
|
||||
Sound,
|
||||
Tamper,
|
||||
Update,
|
||||
Vibration,
|
||||
Window,
|
||||
}
|
||||
|
||||
/// A binary sensor that can publish a [`BinarySensorState`] status.
|
||||
#[derive(Serialize)]
|
||||
pub struct BinarySensor {
|
||||
/// The type of sensor
|
||||
pub device_class: Option<BinarySensorClass>,
|
||||
}
|
||||
|
||||
impl Component for BinarySensor {
|
||||
type State = BinarySensorState;
|
||||
|
||||
fn platform() -> &'static str {
|
||||
"binary_sensor"
|
||||
}
|
||||
|
||||
async fn publish_state<T: Deref<Target = str>>(
|
||||
&self,
|
||||
topic: &Topic<T>,
|
||||
state: Self::State,
|
||||
) -> Result<(), Error> {
|
||||
topic.with_bytes(state).publish().await
|
||||
}
|
||||
}
|
||||
40
rust/src/mcutie_3_0_0/homeassistant/button.rs
Normal file
40
rust/src/mcutie_3_0_0/homeassistant/button.rs
Normal file
@@ -0,0 +1,40 @@
|
||||
//! Tools for publishing a [Home Assistant button](https://www.home-assistant.io/integrations/button.mqtt/).
|
||||
use core::ops::Deref;
|
||||
|
||||
use serde::Serialize;
|
||||
|
||||
use crate::{homeassistant::Component, Error, Topic};
|
||||
|
||||
/// The type of button.
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "snake_case")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum ButtonClass {
|
||||
Identify,
|
||||
Restart,
|
||||
Update,
|
||||
}
|
||||
|
||||
/// A button that can be pressed.
|
||||
#[derive(Serialize)]
|
||||
pub struct Button {
|
||||
/// The type of button.
|
||||
pub device_class: Option<ButtonClass>,
|
||||
}
|
||||
|
||||
impl Component for Button {
|
||||
type State = ();
|
||||
|
||||
fn platform() -> &'static str {
|
||||
"button"
|
||||
}
|
||||
|
||||
async fn publish_state<T: Deref<Target = str>>(
|
||||
&self,
|
||||
_topic: &Topic<T>,
|
||||
_state: Self::State,
|
||||
) -> Result<(), Error> {
|
||||
// Buttons don't have a state
|
||||
Err(Error::Invalid)
|
||||
}
|
||||
}
|
||||
384
rust/src/mcutie_3_0_0/homeassistant/light.rs
Normal file
384
rust/src/mcutie_3_0_0/homeassistant/light.rs
Normal file
@@ -0,0 +1,384 @@
|
||||
//! Tools for publishing a [Home Assistant light](https://www.home-assistant.io/integrations/light.mqtt/).
|
||||
use core::{ops::Deref, str};
|
||||
|
||||
use serde::{ser::SerializeStruct, Deserialize, Serialize, Serializer};
|
||||
|
||||
use crate::{
|
||||
fmt::Debug2Format,
|
||||
homeassistant::{binary_sensor::BinarySensorState, ser::List, Component},
|
||||
Error, Payload, Publishable, Topic,
|
||||
};
|
||||
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "lowercase")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum SupportedColorMode {
|
||||
OnOff,
|
||||
Brightness,
|
||||
#[serde(rename = "color_temp")]
|
||||
ColorTemp,
|
||||
Hs,
|
||||
Xy,
|
||||
Rgb,
|
||||
Rgbw,
|
||||
Rgbww,
|
||||
White,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Deserialize, Default)]
|
||||
struct SerializedColor {
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
h: Option<f32>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
s: Option<f32>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
x: Option<f32>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
y: Option<f32>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
r: Option<u8>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
g: Option<u8>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
b: Option<u8>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
w: Option<u8>,
|
||||
#[serde(default, skip_serializing_if = "Option::is_none")]
|
||||
c: Option<u8>,
|
||||
}
|
||||
|
||||
#[derive(Deserialize)]
|
||||
struct LedPayload<'a> {
|
||||
state: BinarySensorState,
|
||||
#[serde(default)]
|
||||
brightness: Option<u8>,
|
||||
#[serde(default)]
|
||||
color_temp: Option<u32>,
|
||||
#[serde(default)]
|
||||
color: Option<SerializedColor>,
|
||||
#[serde(default)]
|
||||
effect: Option<&'a str>,
|
||||
}
|
||||
|
||||
/// The color of the light in various forms.
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "lowercase", tag = "color_mode", content = "color")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum Color {
|
||||
None,
|
||||
Brightness(u8),
|
||||
ColorTemp(u32),
|
||||
Hs {
|
||||
#[serde(rename = "h")]
|
||||
hue: f32,
|
||||
#[serde(rename = "s")]
|
||||
saturation: f32,
|
||||
},
|
||||
Xy {
|
||||
x: f32,
|
||||
y: f32,
|
||||
},
|
||||
Rgb {
|
||||
#[serde(rename = "r")]
|
||||
red: u8,
|
||||
#[serde(rename = "g")]
|
||||
green: u8,
|
||||
#[serde(rename = "b")]
|
||||
blue: u8,
|
||||
},
|
||||
Rgbw {
|
||||
#[serde(rename = "r")]
|
||||
red: u8,
|
||||
#[serde(rename = "g")]
|
||||
green: u8,
|
||||
#[serde(rename = "b")]
|
||||
blue: u8,
|
||||
#[serde(rename = "w")]
|
||||
white: u8,
|
||||
},
|
||||
Rgbww {
|
||||
#[serde(rename = "r")]
|
||||
red: u8,
|
||||
#[serde(rename = "g")]
|
||||
green: u8,
|
||||
#[serde(rename = "b")]
|
||||
blue: u8,
|
||||
#[serde(rename = "c")]
|
||||
cool_white: u8,
|
||||
#[serde(rename = "w")]
|
||||
warm_white: u8,
|
||||
},
|
||||
}
|
||||
|
||||
/// The state of the light. This can be sent to the broker and received as a
|
||||
/// command from Home Assistant.
|
||||
pub struct LightState<'a> {
|
||||
/// Whether the light is on or off.
|
||||
pub state: BinarySensorState,
|
||||
/// The color of the light.
|
||||
pub color: Color,
|
||||
/// Any effect that is applied.
|
||||
pub effect: Option<&'a str>,
|
||||
}
|
||||
|
||||
impl<'a> LightState<'a> {
|
||||
/// Parses the state from a command payload.
|
||||
pub fn from_payload(payload: &'a Payload) -> Result<Self, Error> {
|
||||
let parsed: LedPayload<'a> = match payload.deserialize_json() {
|
||||
Ok(p) => p,
|
||||
Err(e) => {
|
||||
warn!("Failed to deserialize packet: {:?}", Debug2Format(&e));
|
||||
if let Ok(s) = str::from_utf8(payload) {
|
||||
trace!("{}", s);
|
||||
}
|
||||
return Err(Error::PacketError);
|
||||
}
|
||||
};
|
||||
|
||||
let color = if let Some(color) = parsed.color {
|
||||
if let Some(x) = color.x {
|
||||
Color::Xy {
|
||||
x,
|
||||
y: color.y.unwrap_or_default(),
|
||||
}
|
||||
} else if let Some(h) = color.h {
|
||||
Color::Hs {
|
||||
hue: h,
|
||||
saturation: color.s.unwrap_or_default(),
|
||||
}
|
||||
} else if let Some(c) = color.c {
|
||||
Color::Rgbww {
|
||||
red: color.r.unwrap_or_default(),
|
||||
green: color.g.unwrap_or_default(),
|
||||
blue: color.b.unwrap_or_default(),
|
||||
cool_white: c,
|
||||
warm_white: color.w.unwrap_or_default(),
|
||||
}
|
||||
} else if let Some(w) = color.w {
|
||||
Color::Rgbw {
|
||||
red: color.r.unwrap_or_default(),
|
||||
green: color.g.unwrap_or_default(),
|
||||
blue: color.b.unwrap_or_default(),
|
||||
white: w,
|
||||
}
|
||||
} else {
|
||||
Color::Rgb {
|
||||
red: color.r.unwrap_or_default(),
|
||||
green: color.g.unwrap_or_default(),
|
||||
blue: color.b.unwrap_or_default(),
|
||||
}
|
||||
}
|
||||
} else if let Some(color_temp) = parsed.color_temp {
|
||||
Color::ColorTemp(color_temp)
|
||||
} else if let Some(brightness) = parsed.brightness {
|
||||
Color::Brightness(brightness)
|
||||
} else {
|
||||
Color::None
|
||||
};
|
||||
|
||||
Ok(LightState {
|
||||
state: parsed.state,
|
||||
color,
|
||||
effect: parsed.effect,
|
||||
})
|
||||
}
|
||||
}
|
||||
|
||||
impl Serialize for LightState<'_> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let mut len = 1;
|
||||
|
||||
if self.effect.is_some() {
|
||||
len += 1;
|
||||
}
|
||||
|
||||
match self.color {
|
||||
Color::None => {}
|
||||
Color::Brightness(_) | Color::ColorTemp(_) => len += 1,
|
||||
_ => len += 2,
|
||||
}
|
||||
|
||||
let mut serializer = serializer.serialize_struct("LightState", len)?;
|
||||
|
||||
serializer.serialize_field("state", &self.state)?;
|
||||
|
||||
if let Some(effect) = self.effect {
|
||||
serializer.serialize_field("effect", effect)?;
|
||||
} else {
|
||||
serializer.skip_field("effect")?;
|
||||
}
|
||||
|
||||
match self.color {
|
||||
Color::None => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
serializer.skip_field("color")?;
|
||||
}
|
||||
Color::Brightness(b) => {
|
||||
serializer.skip_field("color_temp")?;
|
||||
serializer.skip_field("color")?;
|
||||
|
||||
serializer.serialize_field("brightness", &b)?
|
||||
}
|
||||
Color::ColorTemp(c) => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color")?;
|
||||
|
||||
serializer.serialize_field("color_temp", &c)?
|
||||
}
|
||||
Color::Hs { hue, saturation } => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
|
||||
serializer.serialize_field("color_mode", "hs")?;
|
||||
|
||||
let color = SerializedColor {
|
||||
h: Some(hue),
|
||||
s: Some(saturation),
|
||||
..Default::default()
|
||||
};
|
||||
|
||||
serializer.serialize_field("color", &color)?
|
||||
}
|
||||
Color::Xy { x, y } => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
|
||||
serializer.serialize_field("color_mode", "xy")?;
|
||||
|
||||
let color = SerializedColor {
|
||||
x: Some(x),
|
||||
y: Some(y),
|
||||
..Default::default()
|
||||
};
|
||||
|
||||
serializer.serialize_field("color", &color)?
|
||||
}
|
||||
Color::Rgb { red, green, blue } => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
|
||||
serializer.serialize_field("color_mode", "rgb")?;
|
||||
|
||||
let color = SerializedColor {
|
||||
r: Some(red),
|
||||
g: Some(green),
|
||||
b: Some(blue),
|
||||
..Default::default()
|
||||
};
|
||||
|
||||
serializer.serialize_field("color", &color)?
|
||||
}
|
||||
Color::Rgbw {
|
||||
red,
|
||||
green,
|
||||
blue,
|
||||
white,
|
||||
} => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
|
||||
serializer.serialize_field("color_mode", "rgbw")?;
|
||||
|
||||
let color = SerializedColor {
|
||||
r: Some(red),
|
||||
g: Some(green),
|
||||
b: Some(blue),
|
||||
w: Some(white),
|
||||
..Default::default()
|
||||
};
|
||||
|
||||
serializer.serialize_field("color", &color)?
|
||||
}
|
||||
Color::Rgbww {
|
||||
red,
|
||||
green,
|
||||
blue,
|
||||
cool_white,
|
||||
warm_white,
|
||||
} => {
|
||||
serializer.skip_field("brightness")?;
|
||||
serializer.skip_field("color_temp")?;
|
||||
|
||||
serializer.serialize_field("color_mode", "rgbww")?;
|
||||
|
||||
let color = SerializedColor {
|
||||
r: Some(red),
|
||||
g: Some(green),
|
||||
b: Some(blue),
|
||||
c: Some(cool_white),
|
||||
w: Some(warm_white),
|
||||
..Default::default()
|
||||
};
|
||||
|
||||
serializer.serialize_field("color", &color)?
|
||||
}
|
||||
}
|
||||
|
||||
serializer.end()
|
||||
}
|
||||
}
|
||||
|
||||
/// A light entity
|
||||
pub struct Light<'a, const C: usize, const E: usize> {
|
||||
/// The color modes supported by the light.
|
||||
pub supported_color_modes: [SupportedColorMode; C],
|
||||
/// Any effects that can be used.
|
||||
pub effects: [&'a str; E],
|
||||
}
|
||||
|
||||
impl<const C: usize, const E: usize> Serialize for Light<'_, C, E> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let mut len = 2;
|
||||
|
||||
if C > 0 {
|
||||
len += 1;
|
||||
}
|
||||
|
||||
if E > 0 {
|
||||
len += 2;
|
||||
}
|
||||
|
||||
let mut serializer = serializer.serialize_struct("Light", len)?;
|
||||
|
||||
serializer.serialize_field("schema", "json")?;
|
||||
|
||||
if C > 0 {
|
||||
serializer.serialize_field("sup_clrm", &List::new(&self.supported_color_modes))?;
|
||||
} else {
|
||||
serializer.skip_field("sup_clrm")?;
|
||||
}
|
||||
|
||||
if E > 0 {
|
||||
serializer.serialize_field("effect", &true)?;
|
||||
serializer.serialize_field("fx_list", &List::new(&self.effects))?;
|
||||
} else {
|
||||
serializer.skip_field("effect")?;
|
||||
serializer.skip_field("fx_list")?;
|
||||
}
|
||||
|
||||
serializer.end()
|
||||
}
|
||||
}
|
||||
|
||||
impl<const C: usize, const E: usize> Component for Light<'_, C, E> {
|
||||
type State = LightState<'static>;
|
||||
|
||||
fn platform() -> &'static str {
|
||||
"light"
|
||||
}
|
||||
|
||||
async fn publish_state<T: Deref<Target = str>>(
|
||||
&self,
|
||||
topic: &Topic<T>,
|
||||
state: Self::State,
|
||||
) -> Result<(), Error> {
|
||||
topic.with_json(state).publish().await
|
||||
}
|
||||
}
|
||||
295
rust/src/mcutie_3_0_0/homeassistant/mod.rs
Normal file
295
rust/src/mcutie_3_0_0/homeassistant/mod.rs
Normal file
@@ -0,0 +1,295 @@
|
||||
//! Home Assistant auto-discovery and related messages.
|
||||
//!
|
||||
//! Normally you would declare your entities statically in your binary. It is
|
||||
//! then trivial to send out discovery messages or state changes.
|
||||
//!
|
||||
//! ```
|
||||
//! # use mcutie::{Publishable, Topic};
|
||||
//! # use mcutie::homeassistant::{Entity, Device, Origin, AvailabilityState, AvailabilityTopics};
|
||||
//! # use mcutie::homeassistant::binary_sensor::{BinarySensor, BinarySensorClass, BinarySensorState};
|
||||
//! const DEVICE_AVAILABILITY_TOPIC: Topic<&'static str> = Topic::Device("status");
|
||||
//! const MOTION_STATE_TOPIC: Topic<&'static str> = Topic::Device("motion/status");
|
||||
//!
|
||||
//! const DEVICE: Device<'static> = Device::new();
|
||||
//! const ORIGIN: Origin<'static> = Origin::new();
|
||||
//!
|
||||
//! const MOTION_SENSOR: Entity<'static, 1, BinarySensor> = Entity {
|
||||
//! device: DEVICE,
|
||||
//! origin: ORIGIN,
|
||||
//! object_id: "motion",
|
||||
//! unique_id: Some("motion"),
|
||||
//! name: "Motion",
|
||||
//! availability: AvailabilityTopics::All([DEVICE_AVAILABILITY_TOPIC]),
|
||||
//! state_topic: Some(MOTION_STATE_TOPIC),
|
||||
//! command_topic: None,
|
||||
//! component: BinarySensor {
|
||||
//! device_class: Some(BinarySensorClass::Motion),
|
||||
//! },
|
||||
//! };
|
||||
//!
|
||||
//! async fn send_discovery_messages() {
|
||||
//! MOTION_SENSOR.publish_discovery().await.unwrap();
|
||||
//! DEVICE_AVAILABILITY_TOPIC.with_bytes(AvailabilityState::Online).publish().await.unwrap();
|
||||
//! }
|
||||
//!
|
||||
//! async fn send_state(state: BinarySensorState) {
|
||||
//! MOTION_SENSOR.publish_state(state).await.unwrap();
|
||||
//! }
|
||||
//! ```
|
||||
use core::{future::Future, ops::Deref};
|
||||
|
||||
use mqttrs::QoS;
|
||||
use serde::{
|
||||
ser::{Error as _, SerializeStruct},
|
||||
Serialize, Serializer,
|
||||
};
|
||||
|
||||
use crate::{
|
||||
device_id, device_type, homeassistant::ser::DiscoverySerializer, io::publish, Error,
|
||||
McutieTask, MqttMessage, Payload, Publishable, Topic, TopicString, DATA_CHANNEL,
|
||||
};
|
||||
|
||||
pub mod binary_sensor;
|
||||
pub mod button;
|
||||
pub mod light;
|
||||
pub mod sensor;
|
||||
mod ser;
|
||||
|
||||
const HA_STATUS_TOPIC: Topic<&'static str> = Topic::General("homeassistant/status");
|
||||
const STATE_ONLINE: &str = "online";
|
||||
const STATE_OFFLINE: &str = "offline";
|
||||
|
||||
/// A trait representing a specific type of entity in Home Assistant
|
||||
pub trait Component: Serialize {
|
||||
/// The state to publish.
|
||||
type State;
|
||||
|
||||
/// The platform identifier for this entity. Internal.
|
||||
fn platform() -> &'static str;
|
||||
|
||||
/// Publishes this entity's state to the MQTT broker.
|
||||
fn publish_state<T: Deref<Target = str>>(
|
||||
&self,
|
||||
topic: &Topic<T>,
|
||||
state: Self::State,
|
||||
) -> impl Future<Output = Result<(), Error>>;
|
||||
}
|
||||
|
||||
impl<'t, T, L, const S: usize> McutieTask<'t, T, L, S>
|
||||
where
|
||||
T: Deref<Target = str> + 't,
|
||||
L: Publishable + 't,
|
||||
{
|
||||
pub(super) async fn ha_after_connected(&self) {
|
||||
let _ = HA_STATUS_TOPIC.subscribe(false).await;
|
||||
}
|
||||
|
||||
pub(super) async fn ha_handle_update(
|
||||
&self,
|
||||
topic: &Topic<TopicString>,
|
||||
payload: &Payload,
|
||||
) -> bool {
|
||||
if topic == &HA_STATUS_TOPIC {
|
||||
if payload.as_ref() == STATE_ONLINE.as_bytes() {
|
||||
DATA_CHANNEL.send(MqttMessage::HomeAssistantOnline).await;
|
||||
}
|
||||
|
||||
true
|
||||
} else {
|
||||
false
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: Deref<Target = str>> Serialize for Topic<T> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: serde::Serializer,
|
||||
{
|
||||
let mut topic = TopicString::new();
|
||||
self.to_string(&mut topic)
|
||||
.map_err(|_| S::Error::custom("topic was too large to serialize"))?;
|
||||
serializer.serialize_str(&topic)
|
||||
}
|
||||
}
|
||||
|
||||
fn name_or_device<S>(name: &Option<&str>, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
serializer.serialize_str(name.unwrap_or_else(|| device_type()))
|
||||
}
|
||||
|
||||
/// Represents the device in Home Assistant.
|
||||
///
|
||||
/// Can just be the default in which case useful properties such as the ID are
|
||||
/// automatically included.
|
||||
#[derive(Clone, Copy, Default)]
|
||||
pub struct Device<'a> {
|
||||
/// A name to identify the device. If not provided the default device type is
|
||||
/// used.
|
||||
pub name: Option<&'a str>,
|
||||
/// An optional configuration URL for the device.
|
||||
pub configuration_url: Option<&'a str>,
|
||||
}
|
||||
|
||||
impl Device<'_> {
|
||||
/// Creates a new default device.
|
||||
pub const fn new() -> Self {
|
||||
Self {
|
||||
name: None,
|
||||
configuration_url: None,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl Serialize for Device<'_> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let mut len = 2;
|
||||
if self.configuration_url.is_some() {
|
||||
len += 1;
|
||||
}
|
||||
|
||||
let mut serializer = serializer.serialize_struct("Device", len)?;
|
||||
|
||||
serializer.serialize_field("name", self.name.unwrap_or_else(|| device_type()))?;
|
||||
serializer.serialize_field("ids", device_id())?;
|
||||
|
||||
if let Some(cu) = self.configuration_url {
|
||||
serializer.serialize_field("cu", cu)?;
|
||||
} else {
|
||||
serializer.skip_field("cu")?;
|
||||
}
|
||||
|
||||
serializer.end()
|
||||
}
|
||||
}
|
||||
|
||||
/// Represents the device's origin in Home Assistant.
|
||||
///
|
||||
/// Can just be the default in which case useful properties are automatically
|
||||
/// included.
|
||||
#[derive(Clone, Copy, Default, Serialize)]
|
||||
pub struct Origin<'a> {
|
||||
/// A name to identify the device's origin. If not provided the default
|
||||
/// device type is used.
|
||||
#[serde(serialize_with = "name_or_device")]
|
||||
pub name: Option<&'a str>,
|
||||
}
|
||||
|
||||
impl Origin<'_> {
|
||||
/// Creates a new default origin.
|
||||
pub const fn new() -> Self {
|
||||
Self { name: None }
|
||||
}
|
||||
}
|
||||
|
||||
/// A single entity for Home Assistant.
|
||||
///
|
||||
/// Calling [`Entity::publish_discovery`] will publish the discovery message to
|
||||
/// allow Home Assistant to detect this entity. Read the
|
||||
/// [Home Assistant MQTT docs](https://www.home-assistant.io/integrations/mqtt/)
|
||||
/// for information on what some of these properties mean.
|
||||
pub struct Entity<'a, const A: usize, C: Component> {
|
||||
/// The device this entity is a part of.
|
||||
pub device: Device<'a>,
|
||||
/// The origin of the device.
|
||||
pub origin: Origin<'a>,
|
||||
/// An object identifier to allow for entity ID customisation in Home Assistant.
|
||||
pub object_id: &'a str,
|
||||
/// An optional unique identifier for the entity.
|
||||
pub unique_id: Option<&'a str>,
|
||||
/// A friendly name for the entity.
|
||||
pub name: &'a str,
|
||||
/// Specifies the availability topics that Home Assistant will listen to to
|
||||
/// determine this entity's availability.
|
||||
pub availability: AvailabilityTopics<'a, A>,
|
||||
/// The state topic that this entity's state is published to.
|
||||
pub state_topic: Option<Topic<&'a str>>,
|
||||
/// The command topic that this entity receives commands from.
|
||||
pub command_topic: Option<Topic<&'a str>>,
|
||||
/// The specific entity.
|
||||
pub component: C,
|
||||
}
|
||||
|
||||
impl<const A: usize, C: Component> Entity<'_, A, C> {
|
||||
/// Publishes the discovery message for this entity to the broker.
|
||||
pub async fn publish_discovery(&self) -> Result<(), Error> {
|
||||
let mut topic = TopicString::new();
|
||||
topic
|
||||
.push_str(option_env!("HA_DISCOVERY_PREFIX").unwrap_or("homeassistant"))
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
topic.push('/').map_err(|_| Error::TooLarge)?;
|
||||
topic.push_str(C::platform()).map_err(|_| Error::TooLarge)?;
|
||||
topic.push('/').map_err(|_| Error::TooLarge)?;
|
||||
topic
|
||||
.push_str(self.object_id)
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
topic.push_str("/config").map_err(|_| Error::TooLarge)?;
|
||||
|
||||
let mut payload = Payload::new();
|
||||
payload.serialize_json(self).map_err(|_| Error::TooLarge)?;
|
||||
|
||||
publish(&topic, &payload, QoS::AtMostOnce, false).await
|
||||
}
|
||||
|
||||
/// Publishes this entity's state to the broker.
|
||||
///
|
||||
/// # Errors
|
||||
///
|
||||
/// - [`Error::Invalid`] if the entity doesn't have a state topic.
|
||||
pub async fn publish_state(&self, state: C::State) -> Result<(), Error> {
|
||||
if let Some(topic) = self.state_topic {
|
||||
self.component.publish_state(&topic, state).await
|
||||
} else {
|
||||
Err(Error::Invalid)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// A payload representing a device or entity's availability.
|
||||
#[allow(missing_docs)]
|
||||
pub enum AvailabilityState {
|
||||
Online,
|
||||
Offline,
|
||||
}
|
||||
|
||||
impl AsRef<[u8]> for AvailabilityState {
|
||||
fn as_ref(&self) -> &'static [u8] {
|
||||
match self {
|
||||
Self::Online => STATE_ONLINE.as_bytes(),
|
||||
Self::Offline => STATE_OFFLINE.as_bytes(),
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// The availiabity topics that home assistant will use to determine an entity's
|
||||
/// availability.
|
||||
pub enum AvailabilityTopics<'a, const A: usize> {
|
||||
/// The entity is always available.
|
||||
None,
|
||||
/// The entity is available if all of the topics are publishes as online.
|
||||
All([Topic<&'a str>; A]),
|
||||
/// The entity is available if any of the topics are publishes as online.
|
||||
Any([Topic<&'a str>; A]),
|
||||
/// The entity is available based on the most recent of the topics to
|
||||
/// publish state.
|
||||
Latest([Topic<&'a str>; A]),
|
||||
}
|
||||
|
||||
impl<const A: usize, C: Component> Serialize for Entity<'_, A, C> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let outer = DiscoverySerializer {
|
||||
discovery: self,
|
||||
inner: serializer,
|
||||
};
|
||||
|
||||
self.component.serialize(outer)
|
||||
}
|
||||
}
|
||||
103
rust/src/mcutie_3_0_0/homeassistant/sensor.rs
Normal file
103
rust/src/mcutie_3_0_0/homeassistant/sensor.rs
Normal file
@@ -0,0 +1,103 @@
|
||||
//! Tools for publishing a [Home Assistant sensor](https://www.home-assistant.io/integrations/sensor.mqtt/).
|
||||
use core::ops::Deref;
|
||||
|
||||
use serde::Serialize;
|
||||
|
||||
use crate::{homeassistant::Component, Error, Publishable, Topic};
|
||||
|
||||
/// The type of sensor.
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "snake_case")]
|
||||
#[allow(missing_docs)]
|
||||
pub enum SensorClass {
|
||||
ApparentPower,
|
||||
Aqi,
|
||||
AtmosphericPressure,
|
||||
Battery,
|
||||
CarbonDioxide,
|
||||
CarbonMonoxide,
|
||||
Current,
|
||||
DataRate,
|
||||
DataSize,
|
||||
Date,
|
||||
Distance,
|
||||
Duration,
|
||||
Energy,
|
||||
EnergyStorage,
|
||||
Enum,
|
||||
Frequency,
|
||||
Gas,
|
||||
Humidity,
|
||||
Illuminance,
|
||||
Irradiance,
|
||||
Moisture,
|
||||
Monetary,
|
||||
NitrogenDioxide,
|
||||
NitrogenMonoxide,
|
||||
NitrousOxide,
|
||||
Ozone,
|
||||
Ph,
|
||||
Pm1,
|
||||
Pm25,
|
||||
Pm10,
|
||||
PowerFactor,
|
||||
Power,
|
||||
Precipitation,
|
||||
PrecipitationIntensity,
|
||||
Pressure,
|
||||
ReactivePower,
|
||||
SignalStrength,
|
||||
SoundPressure,
|
||||
Speed,
|
||||
SulphurDioxide,
|
||||
Temperature,
|
||||
Timestamp,
|
||||
VolatileOrganicCompounds,
|
||||
VolatileOrganicCompoundsParts,
|
||||
Voltage,
|
||||
Volume,
|
||||
VolumeFlowRate,
|
||||
VolumeStorage,
|
||||
Water,
|
||||
Weight,
|
||||
WindSpeed,
|
||||
}
|
||||
|
||||
/// The type of measurement that this entity publishes.
|
||||
#[derive(Serialize)]
|
||||
#[serde(rename_all = "snake_case")]
|
||||
pub enum SensorStateClass {
|
||||
/// A measurement at a singe point in time.
|
||||
Measurement,
|
||||
/// A cumulative total that can increase or decrease over time.
|
||||
Total,
|
||||
/// A cumulative total that can only increase.
|
||||
TotalIncreasing,
|
||||
}
|
||||
|
||||
/// A binary sensor that can publish a [`f32`] value.
|
||||
#[derive(Serialize)]
|
||||
pub struct Sensor<'u> {
|
||||
/// The type of sensor.
|
||||
pub device_class: Option<SensorClass>,
|
||||
/// The type of measurement that this sensor reports.
|
||||
pub state_class: Option<SensorStateClass>,
|
||||
/// The unit of measurement for this sensor.
|
||||
pub unit_of_measurement: Option<&'u str>,
|
||||
}
|
||||
|
||||
impl Component for Sensor<'_> {
|
||||
type State = f32;
|
||||
|
||||
fn platform() -> &'static str {
|
||||
"sensor"
|
||||
}
|
||||
|
||||
async fn publish_state<T: Deref<Target = str>>(
|
||||
&self,
|
||||
topic: &Topic<T>,
|
||||
state: Self::State,
|
||||
) -> Result<(), Error> {
|
||||
topic.with_display(state).publish().await
|
||||
}
|
||||
}
|
||||
333
rust/src/mcutie_3_0_0/homeassistant/ser.rs
Normal file
333
rust/src/mcutie_3_0_0/homeassistant/ser.rs
Normal file
@@ -0,0 +1,333 @@
|
||||
use core::ops::Deref;
|
||||
|
||||
use serde::{
|
||||
ser::{SerializeSeq, SerializeStruct},
|
||||
Serialize, Serializer,
|
||||
};
|
||||
|
||||
use crate::{
|
||||
homeassistant::{AvailabilityTopics, Component, Entity},
|
||||
Topic,
|
||||
};
|
||||
|
||||
#[derive(Serialize)]
|
||||
pub(super) struct AvailabilityTopicItem<'a> {
|
||||
topic: Topic<&'a str>,
|
||||
}
|
||||
|
||||
struct AvailabilityTopicList<'a, T: Deref<Target = str>, const N: usize> {
|
||||
list: &'a [Topic<T>; N],
|
||||
}
|
||||
|
||||
impl<'a, const N: usize, T: Deref<Target = str>> AvailabilityTopicList<'a, T, N> {
|
||||
pub(super) fn new(list: &'a [Topic<T>; N]) -> Self {
|
||||
Self { list }
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: Deref<Target = str>, const N: usize> Serialize for AvailabilityTopicList<'_, T, N> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let mut serializer = serializer.serialize_seq(Some(N))?;
|
||||
|
||||
for topic in self.list {
|
||||
serializer.serialize_element(&AvailabilityTopicItem {
|
||||
topic: topic.as_ref(),
|
||||
})?;
|
||||
}
|
||||
|
||||
serializer.end()
|
||||
}
|
||||
}
|
||||
|
||||
pub(super) struct List<'a, T: Serialize, const N: usize> {
|
||||
list: &'a [T; N],
|
||||
}
|
||||
|
||||
impl<'a, T: Serialize, const N: usize> List<'a, T, N> {
|
||||
pub(super) fn new(list: &'a [T; N]) -> Self {
|
||||
Self { list }
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: Serialize, const N: usize> Serialize for List<'_, T, N> {
|
||||
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
|
||||
where
|
||||
S: Serializer,
|
||||
{
|
||||
let mut serializer = serializer.serialize_seq(Some(N))?;
|
||||
|
||||
for item in self.list {
|
||||
serializer.serialize_element(item)?;
|
||||
}
|
||||
|
||||
serializer.end()
|
||||
}
|
||||
}
|
||||
|
||||
pub(super) struct DiscoverySerializer<'a, const A: usize, C: Component, S: Serializer> {
|
||||
pub(super) discovery: &'a Entity<'a, A, C>,
|
||||
pub(super) inner: S,
|
||||
}
|
||||
|
||||
impl<const A: usize, C: Component, S: Serializer> Serializer for DiscoverySerializer<'_, A, C, S> {
|
||||
type Ok = S::Ok;
|
||||
type Error = S::Error;
|
||||
type SerializeSeq = S::SerializeSeq;
|
||||
type SerializeTuple = S::SerializeTuple;
|
||||
type SerializeTupleStruct = S::SerializeTupleStruct;
|
||||
type SerializeTupleVariant = S::SerializeTupleVariant;
|
||||
type SerializeMap = S::SerializeMap;
|
||||
type SerializeStruct = S::SerializeStruct;
|
||||
type SerializeStructVariant = S::SerializeStructVariant;
|
||||
|
||||
fn serialize_struct(
|
||||
self,
|
||||
name: &'static str,
|
||||
mut len: usize,
|
||||
) -> Result<Self::SerializeStruct, Self::Error> {
|
||||
len += 5;
|
||||
if self.discovery.state_topic.is_some() {
|
||||
len += 1;
|
||||
}
|
||||
if self.discovery.command_topic.is_some() {
|
||||
len += 1;
|
||||
}
|
||||
if self.discovery.unique_id.is_some() {
|
||||
len += 1;
|
||||
}
|
||||
if !matches!(self.discovery.availability, AvailabilityTopics::None) {
|
||||
len += 2;
|
||||
}
|
||||
|
||||
let mut serializer = self.inner.serialize_struct(name, len)?;
|
||||
|
||||
serializer.serialize_field("dev", &self.discovery.device)?;
|
||||
serializer.serialize_field("o", &self.discovery.origin)?;
|
||||
serializer.serialize_field("p", C::platform())?;
|
||||
serializer.serialize_field("obj_id", self.discovery.object_id)?;
|
||||
|
||||
serializer.serialize_field("name", self.discovery.name)?;
|
||||
|
||||
if let Some(t) = self.discovery.state_topic {
|
||||
serializer.serialize_field("stat_t", &t)?;
|
||||
} else {
|
||||
serializer.skip_field("stat_t")?;
|
||||
}
|
||||
|
||||
if let Some(t) = self.discovery.command_topic {
|
||||
serializer.serialize_field("cmd_t", &t)?;
|
||||
} else {
|
||||
serializer.skip_field("cmd_t")?;
|
||||
}
|
||||
|
||||
match &self.discovery.availability {
|
||||
AvailabilityTopics::None => {
|
||||
serializer.skip_field("avty")?;
|
||||
serializer.skip_field("avty_mode")?;
|
||||
}
|
||||
AvailabilityTopics::All(topics) => {
|
||||
serializer.serialize_field("avty_mode", "all")?;
|
||||
serializer.serialize_field("avty", &AvailabilityTopicList::new(topics))?;
|
||||
}
|
||||
AvailabilityTopics::Any(topics) => {
|
||||
serializer.serialize_field("avty_mode", "any")?;
|
||||
serializer.serialize_field("avty", &AvailabilityTopicList::new(topics))?;
|
||||
}
|
||||
AvailabilityTopics::Latest(topics) => {
|
||||
serializer.serialize_field("avty_mode", "latest")?;
|
||||
serializer.serialize_field("avty", &AvailabilityTopicList::new(topics))?;
|
||||
}
|
||||
}
|
||||
|
||||
if let Some(v) = self.discovery.unique_id {
|
||||
serializer.serialize_field("uniq_id", v)?;
|
||||
} else {
|
||||
serializer.skip_field("uniq_id")?;
|
||||
}
|
||||
|
||||
Ok(serializer)
|
||||
}
|
||||
|
||||
fn serialize_bool(self, _: bool) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_i8(self, _: i8) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_i16(self, _: i16) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_i32(self, _: i32) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_i64(self, _: i64) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_u8(self, _: u8) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_u16(self, _: u16) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_u32(self, _: u32) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_u64(self, _: u64) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_f32(self, _: f32) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_f64(self, _: f64) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_char(self, _: char) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_str(self, _: &str) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_bytes(self, _: &[u8]) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_none(self) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_some<T>(self, _: &T) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
T: ?Sized + Serialize,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_unit(self) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_unit_struct(self, _: &'static str) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_unit_variant(
|
||||
self,
|
||||
_: &'static str,
|
||||
_: u32,
|
||||
_: &'static str,
|
||||
) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_newtype_struct<T>(self, _: &'static str, _: &T) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
T: ?Sized + Serialize,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_newtype_variant<T>(
|
||||
self,
|
||||
_: &'static str,
|
||||
_: u32,
|
||||
_: &'static str,
|
||||
_: &T,
|
||||
) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
T: ?Sized + Serialize,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_seq(self, _: Option<usize>) -> Result<Self::SerializeSeq, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_tuple(self, _: usize) -> Result<Self::SerializeTuple, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_tuple_struct(
|
||||
self,
|
||||
_: &'static str,
|
||||
_: usize,
|
||||
) -> Result<Self::SerializeTupleStruct, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_tuple_variant(
|
||||
self,
|
||||
_: &'static str,
|
||||
_: u32,
|
||||
_: &'static str,
|
||||
_: usize,
|
||||
) -> Result<Self::SerializeTupleVariant, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_map(self, _: Option<usize>) -> Result<Self::SerializeMap, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_struct_variant(
|
||||
self,
|
||||
_: &'static str,
|
||||
_: u32,
|
||||
_: &'static str,
|
||||
_: usize,
|
||||
) -> Result<Self::SerializeStructVariant, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_i128(self, _: i128) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn serialize_u128(self, _: u128) -> Result<Self::Ok, Self::Error> {
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn collect_seq<I>(self, _: I) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
I: IntoIterator,
|
||||
<I as IntoIterator>::Item: Serialize,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn collect_map<K, V, I>(self, _: I) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
K: Serialize,
|
||||
V: Serialize,
|
||||
I: IntoIterator<Item = (K, V)>,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn collect_str<T>(self, _: &T) -> Result<Self::Ok, Self::Error>
|
||||
where
|
||||
T: ?Sized + core::fmt::Display,
|
||||
{
|
||||
unimplemented!()
|
||||
}
|
||||
|
||||
fn is_human_readable(&self) -> bool {
|
||||
unimplemented!()
|
||||
}
|
||||
}
|
||||
483
rust/src/mcutie_3_0_0/io.rs
Normal file
483
rust/src/mcutie_3_0_0/io.rs
Normal file
@@ -0,0 +1,483 @@
|
||||
use core::ops::Deref;
|
||||
|
||||
pub(crate) use atomic16::assign_pid;
|
||||
use embassy_futures::select::{select, select4, Either};
|
||||
use embassy_net::{
|
||||
dns::DnsQueryType,
|
||||
tcp::{TcpReader, TcpSocket, TcpWriter},
|
||||
Stack,
|
||||
};
|
||||
use embassy_sync::{
|
||||
blocking_mutex::raw::CriticalSectionRawMutex,
|
||||
pubsub::{PubSubChannel, Subscriber, WaitResult},
|
||||
};
|
||||
use embassy_time::Timer;
|
||||
use embedded_io_async::Write;
|
||||
use mqttrs::{
|
||||
decode_slice, Connect, ConnectReturnCode, LastWill, Packet, Pid, Protocol, Publish, QoS, QosPid,
|
||||
};
|
||||
|
||||
use crate::{
|
||||
device_id, fmt::Debug2Format, pipe::ConnectedPipe, ControlMessage, Error, MqttMessage, Payload,
|
||||
Publishable, Topic, TopicString, CONFIRMATION_TIMEOUT, DATA_CHANNEL, DEFAULT_BACKOFF,
|
||||
RESET_BACKOFF,
|
||||
};
|
||||
|
||||
static SEND_QUEUE: ConnectedPipe<CriticalSectionRawMutex, Payload, 10> = ConnectedPipe::new();
|
||||
|
||||
pub(crate) static CONTROL_CHANNEL: PubSubChannel<CriticalSectionRawMutex, ControlMessage, 2, 5, 0> =
|
||||
PubSubChannel::new();
|
||||
|
||||
type ControlSubscriber = Subscriber<'static, CriticalSectionRawMutex, ControlMessage, 2, 5, 0>;
|
||||
|
||||
pub(crate) async fn subscribe() -> ControlSubscriber {
|
||||
loop {
|
||||
if let Ok(sub) = CONTROL_CHANNEL.subscriber() {
|
||||
return sub;
|
||||
}
|
||||
|
||||
Timer::after_millis(50).await;
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(target_has_atomic = "16")]
|
||||
mod atomic16 {
|
||||
use core::sync::atomic::{AtomicU16, Ordering};
|
||||
|
||||
use mqttrs::Pid;
|
||||
|
||||
static PID: AtomicU16 = AtomicU16::new(0);
|
||||
|
||||
pub(crate) async fn assign_pid() -> Pid {
|
||||
Pid::new() + PID.fetch_add(1, Ordering::SeqCst)
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(not(target_has_atomic = "16"))]
|
||||
mod atomic16 {
|
||||
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, mutex::Mutex};
|
||||
use mqttrs::Pid;
|
||||
|
||||
static PID_MUTEX: Mutex<CriticalSectionRawMutex, u16> = Mutex::new(0);
|
||||
|
||||
pub(crate) async fn assign_pid() -> Pid {
|
||||
let mut locked = PID_MUTEX.lock().await;
|
||||
*locked += 1;
|
||||
|
||||
Pid::new() + *locked
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn send_packet(packet: Packet<'_>) -> Result<(), Error> {
|
||||
let mut buffer = Payload::new();
|
||||
|
||||
match buffer.encode_packet(&packet) {
|
||||
Ok(()) => {
|
||||
debug!(
|
||||
"Sending packet to broker: {:?}",
|
||||
Debug2Format(&packet.get_type())
|
||||
);
|
||||
SEND_QUEUE.push(buffer).await;
|
||||
Ok(())
|
||||
}
|
||||
Err(_) => {
|
||||
error!("Failed to send packet");
|
||||
Err(Error::PacketError)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn wait_for_publish(
|
||||
mut subscriber: ControlSubscriber,
|
||||
expected_pid: Pid,
|
||||
) -> Result<(), Error> {
|
||||
match select(
|
||||
async {
|
||||
loop {
|
||||
match subscriber.next_message().await {
|
||||
WaitResult::Lagged(_) => {
|
||||
// Maybe we missed the message?
|
||||
}
|
||||
WaitResult::Message(ControlMessage::Published(published_pid)) => {
|
||||
if published_pid == expected_pid {
|
||||
return Ok(());
|
||||
}
|
||||
}
|
||||
_ => {}
|
||||
}
|
||||
}
|
||||
},
|
||||
Timer::after_millis(CONFIRMATION_TIMEOUT),
|
||||
)
|
||||
.await
|
||||
{
|
||||
Either::First(r) => r,
|
||||
Either::Second(_) => Err(Error::TimedOut),
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) async fn publish(
|
||||
topic_name: &str,
|
||||
payload: &[u8],
|
||||
qos: QoS,
|
||||
retain: bool,
|
||||
) -> Result<(), Error> {
|
||||
let subscriber = subscribe().await;
|
||||
|
||||
let (qospid, pid) = match qos {
|
||||
QoS::AtMostOnce => (QosPid::AtMostOnce, None),
|
||||
QoS::AtLeastOnce => {
|
||||
let pid = assign_pid().await;
|
||||
(QosPid::AtLeastOnce(pid), Some(pid))
|
||||
}
|
||||
QoS::ExactlyOnce => {
|
||||
let pid = assign_pid().await;
|
||||
(QosPid::ExactlyOnce(pid), Some(pid))
|
||||
}
|
||||
};
|
||||
|
||||
let packet = Packet::Publish(Publish {
|
||||
dup: false,
|
||||
qospid,
|
||||
retain,
|
||||
topic_name,
|
||||
payload,
|
||||
});
|
||||
|
||||
send_packet(packet).await?;
|
||||
|
||||
if let Some(expected_pid) = pid {
|
||||
wait_for_publish(subscriber, expected_pid).await
|
||||
} else {
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
|
||||
fn packet_size(buffer: &[u8]) -> Option<usize> {
|
||||
let mut pos = 1;
|
||||
let mut multiplier = 1;
|
||||
let mut value = 0;
|
||||
|
||||
while pos < buffer.len() {
|
||||
value += (buffer[pos] & 127) as usize * multiplier;
|
||||
multiplier *= 128;
|
||||
|
||||
if (buffer[pos] & 128) == 0 {
|
||||
return Some(value + pos + 1);
|
||||
}
|
||||
|
||||
pos += 1;
|
||||
if pos == 5 {
|
||||
return Some(0);
|
||||
}
|
||||
}
|
||||
|
||||
None
|
||||
}
|
||||
|
||||
/// The MQTT task that must be run in order for the stack to operate.
|
||||
pub struct McutieTask<'t, T, L, const S: usize>
|
||||
where
|
||||
T: Deref<Target = str> + 't,
|
||||
L: Publishable + 't,
|
||||
{
|
||||
pub(crate) network: Stack<'t>,
|
||||
pub(crate) broker: &'t str,
|
||||
pub(crate) last_will: Option<L>,
|
||||
pub(crate) username: Option<&'t str>,
|
||||
pub(crate) password: Option<&'t str>,
|
||||
pub(crate) subscriptions: [Topic<T>; S],
|
||||
pub(crate) keep_alive: u16
|
||||
}
|
||||
|
||||
impl<'t, T, L, const S: usize> McutieTask<'t, T, L, S>
|
||||
where
|
||||
T: Deref<Target = str> + 't,
|
||||
L: Publishable + 't,
|
||||
{
|
||||
#[cfg(not(feature = "homeassistant"))]
|
||||
async fn ha_handle_update(&self, _topic: &Topic<TopicString>, _payload: &Payload) -> bool {
|
||||
false
|
||||
}
|
||||
|
||||
async fn recv_loop(&self, mut reader: TcpReader<'_>) -> Result<(), Error> {
|
||||
let mut buffer = [0_u8; 4096];
|
||||
let mut cursor: usize = 0;
|
||||
|
||||
let controller = CONTROL_CHANNEL.immediate_publisher();
|
||||
|
||||
loop {
|
||||
match reader.read(&mut buffer[cursor..]).await {
|
||||
Ok(0) => {
|
||||
error!("Receive socket closed");
|
||||
return Ok(());
|
||||
}
|
||||
Ok(len) => {
|
||||
cursor += len;
|
||||
}
|
||||
Err(_) => {
|
||||
error!("I/O failure reading packet");
|
||||
return Err(Error::IOError);
|
||||
}
|
||||
}
|
||||
|
||||
let mut start_pos = 0;
|
||||
loop {
|
||||
let packet_length = match packet_size(&buffer[start_pos..cursor]) {
|
||||
Some(0) => {
|
||||
error!("Invalid MQTT packet");
|
||||
return Err(Error::PacketError);
|
||||
}
|
||||
Some(len) => len,
|
||||
None => {
|
||||
// None is returned when there is not yet enough data to decode a packet.
|
||||
if start_pos != 0 {
|
||||
// Adjust the buffer to reclaim any unused data
|
||||
buffer.copy_within(start_pos..cursor, 0);
|
||||
cursor -= start_pos;
|
||||
}
|
||||
break;
|
||||
}
|
||||
};
|
||||
|
||||
let packet = match decode_slice(&buffer[start_pos..(start_pos + packet_length)]) {
|
||||
Ok(Some(p)) => p,
|
||||
Ok(None) => {
|
||||
error!("Packet length calculation failed.");
|
||||
return Err(Error::PacketError);
|
||||
}
|
||||
Err(_) => {
|
||||
error!("Invalid MQTT packet");
|
||||
return Err(Error::PacketError);
|
||||
}
|
||||
};
|
||||
|
||||
debug!(
|
||||
"Received packet from broker: {:?}",
|
||||
Debug2Format(&packet.get_type())
|
||||
);
|
||||
|
||||
match packet {
|
||||
Packet::Connack(connack) => match connack.code {
|
||||
ConnectReturnCode::Accepted => {
|
||||
#[cfg(feature = "homeassistant")]
|
||||
self.ha_after_connected().await;
|
||||
|
||||
for topic in &self.subscriptions {
|
||||
let _ = topic.subscribe(false).await;
|
||||
}
|
||||
|
||||
DATA_CHANNEL.send(MqttMessage::Connected).await;
|
||||
}
|
||||
_ => {
|
||||
error!("Connection request to broker was not accepted");
|
||||
return Err(Error::IOError);
|
||||
}
|
||||
},
|
||||
Packet::Pingresp => {}
|
||||
|
||||
Packet::Publish(publish) => {
|
||||
match (
|
||||
Topic::from_str(publish.topic_name),
|
||||
Payload::from(publish.payload),
|
||||
) {
|
||||
(Ok(topic), Ok(payload)) => {
|
||||
if !self.ha_handle_update(&topic, &payload).await {
|
||||
DATA_CHANNEL
|
||||
.send(MqttMessage::Publish(topic, payload))
|
||||
.await;
|
||||
}
|
||||
}
|
||||
_ => {
|
||||
error!("Unable to process publish data as it was too large");
|
||||
}
|
||||
}
|
||||
|
||||
match publish.qospid {
|
||||
mqttrs::QosPid::AtMostOnce => {}
|
||||
mqttrs::QosPid::AtLeastOnce(pid) => {
|
||||
send_packet(Packet::Puback(pid)).await?;
|
||||
}
|
||||
mqttrs::QosPid::ExactlyOnce(pid) => {
|
||||
send_packet(Packet::Pubrec(pid)).await?;
|
||||
}
|
||||
}
|
||||
}
|
||||
Packet::Puback(pid) => {
|
||||
controller.publish_immediate(ControlMessage::Published(pid));
|
||||
}
|
||||
Packet::Pubrec(pid) => {
|
||||
controller.publish_immediate(ControlMessage::Published(pid));
|
||||
send_packet(Packet::Pubrel(pid)).await?;
|
||||
}
|
||||
Packet::Pubrel(pid) => send_packet(Packet::Pubrel(pid)).await?,
|
||||
Packet::Pubcomp(_) => {}
|
||||
|
||||
Packet::Suback(suback) => {
|
||||
if let Some(return_code) = suback.return_codes.first() {
|
||||
controller.publish_immediate(ControlMessage::Subscribed(
|
||||
suback.pid,
|
||||
*return_code,
|
||||
));
|
||||
} else {
|
||||
warn!("Unexpected suback with no return codes");
|
||||
}
|
||||
}
|
||||
Packet::Unsuback(pid) => {
|
||||
controller.publish_immediate(ControlMessage::Unsubscribed(pid));
|
||||
}
|
||||
|
||||
Packet::Connect(_)
|
||||
| Packet::Subscribe(_)
|
||||
| Packet::Pingreq
|
||||
| Packet::Unsubscribe(_)
|
||||
| Packet::Disconnect => {
|
||||
debug!(
|
||||
"Unexpected packet from broker: {:?}",
|
||||
Debug2Format(&packet.get_type())
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
start_pos += packet_length;
|
||||
if start_pos == cursor {
|
||||
cursor = 0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
async fn write_loop(&self, mut writer: TcpWriter<'_>) {
|
||||
let mut buffer = Payload::new();
|
||||
|
||||
let mut last_will_topic = TopicString::new();
|
||||
let mut last_will_payload = Payload::new();
|
||||
|
||||
let last_will = self.last_will.as_ref().and_then(|p| {
|
||||
if p.write_topic(&mut last_will_topic).is_ok()
|
||||
&& p.write_payload(&mut last_will_payload).is_ok()
|
||||
{
|
||||
Some(LastWill {
|
||||
topic: &last_will_topic,
|
||||
message: &last_will_payload,
|
||||
qos: p.qos(),
|
||||
retain: p.retain(),
|
||||
})
|
||||
} else {
|
||||
None
|
||||
}
|
||||
});
|
||||
|
||||
// Send our connection request.
|
||||
if buffer
|
||||
.encode_packet(&Packet::Connect(Connect {
|
||||
protocol: Protocol::MQTT311,
|
||||
keep_alive: self.keep_alive,
|
||||
client_id: device_id(),
|
||||
clean_session: true,
|
||||
last_will,
|
||||
username: self.username,
|
||||
password: self.password.map(|s| s.as_bytes()),
|
||||
}))
|
||||
.is_err()
|
||||
{
|
||||
error!("Failed to encode connection packet");
|
||||
return;
|
||||
}
|
||||
|
||||
if let Err(e) = writer.write(&buffer).await {
|
||||
error!("Failed to send connection packet: {:?}", e);
|
||||
return;
|
||||
}
|
||||
|
||||
let reader = SEND_QUEUE.reader();
|
||||
|
||||
loop {
|
||||
let buffer = reader.receive().await;
|
||||
|
||||
trace!("Writer sending packet");
|
||||
if let Err(e) = writer.write(&buffer).await {
|
||||
error!("Failed to send data: {:?}", e);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Runs the MQTT stack. The future returned from this must be awaited for everything to work.
|
||||
pub async fn run(self) {
|
||||
let mut timeout: Option<u64> = None;
|
||||
|
||||
let mut rx_buffer = [0; 4096];
|
||||
let mut tx_buffer = [0; 4096];
|
||||
|
||||
loop {
|
||||
if let Some(millis) = timeout.replace(DEFAULT_BACKOFF) {
|
||||
Timer::after_millis(millis).await;
|
||||
}
|
||||
|
||||
if !self.network.is_config_up() {
|
||||
debug!("Waiting for network to configure.");
|
||||
self.network.wait_config_up().await;
|
||||
debug!("Network configured.");
|
||||
}
|
||||
|
||||
let ip_addrs = match self.network.dns_query(self.broker, DnsQueryType::A).await {
|
||||
Ok(v) => v,
|
||||
Err(e) => {
|
||||
error!("Failed to lookup '{}' for broker: {:?}", self.broker, e);
|
||||
continue;
|
||||
}
|
||||
};
|
||||
|
||||
let ip = match ip_addrs.first() {
|
||||
Some(i) => *i,
|
||||
None => {
|
||||
error!("No IP address found for broker '{}'", self.broker);
|
||||
continue;
|
||||
}
|
||||
};
|
||||
|
||||
debug!("Connecting to {}:1883", ip);
|
||||
|
||||
let mut socket = TcpSocket::new(self.network, &mut rx_buffer, &mut tx_buffer);
|
||||
if let Err(e) = socket.connect((ip, 1883)).await {
|
||||
error!("Failed to connect to {}:1883: {:?}", ip, e);
|
||||
continue;
|
||||
}
|
||||
|
||||
info!("Connected to {}", self.broker);
|
||||
timeout = Some(RESET_BACKOFF);
|
||||
|
||||
let (reader, writer) = socket.split();
|
||||
|
||||
let recv_loop = self.recv_loop(reader);
|
||||
let send_loop = self.write_loop(writer);
|
||||
|
||||
let ping_loop = async {
|
||||
loop {
|
||||
Timer::after_secs(45).await;
|
||||
|
||||
let _ = send_packet(Packet::Pingreq).await;
|
||||
}
|
||||
};
|
||||
|
||||
let link_down = async {
|
||||
self.network.wait_link_down().await;
|
||||
warn!("Network link lost");
|
||||
};
|
||||
|
||||
let ip_down = async {
|
||||
self.network.wait_config_down().await;
|
||||
warn!("Network config lost");
|
||||
};
|
||||
|
||||
select4(send_loop, ping_loop, recv_loop, select(link_down, ip_down)).await;
|
||||
|
||||
socket.close();
|
||||
|
||||
warn!("Lost connection with broker");
|
||||
DATA_CHANNEL.send(MqttMessage::Disconnected).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
227
rust/src/mcutie_3_0_0/lib.rs
Normal file
227
rust/src/mcutie_3_0_0/lib.rs
Normal file
@@ -0,0 +1,227 @@
|
||||
#![no_std]
|
||||
#![deny(unreachable_pub)]
|
||||
#![warn(missing_docs)]
|
||||
#![cfg_attr(docsrs, feature(doc_auto_cfg))]
|
||||
//! MQTT client support crate vendored into this repository.
|
||||
|
||||
use core::{ops::Deref, str};
|
||||
|
||||
pub use buffer::Buffer;
|
||||
use embassy_net::{HardwareAddress, Stack};
|
||||
use embassy_sync::{blocking_mutex::raw::CriticalSectionRawMutex, channel::Channel};
|
||||
use heapless::String;
|
||||
pub use io::McutieTask;
|
||||
pub use mqttrs::QoS;
|
||||
use mqttrs::{Pid, SubscribeReturnCodes};
|
||||
use once_cell::sync::OnceCell;
|
||||
pub use publish::*;
|
||||
pub use topic::Topic;
|
||||
|
||||
// This must come first so the macros are visible
|
||||
pub(crate) mod fmt;
|
||||
|
||||
mod buffer;
|
||||
#[cfg(feature = "homeassistant")]
|
||||
pub mod homeassistant;
|
||||
mod io;
|
||||
mod pipe;
|
||||
mod publish;
|
||||
mod topic;
|
||||
|
||||
// This really needs to match that used by mqttrs.
|
||||
const TOPIC_LENGTH: usize = 256;
|
||||
const PAYLOAD_LENGTH: usize = 2048;
|
||||
|
||||
/// A fixed length stack allocated string. The length is fixed by the mqttrs crate.
|
||||
pub type TopicString = String<TOPIC_LENGTH>;
|
||||
/// A fixed length buffer of 2048 bytes.
|
||||
pub type Payload = Buffer<PAYLOAD_LENGTH>;
|
||||
|
||||
// By default in the event of an error connecting to the broker we will wait for 5s.
|
||||
const DEFAULT_BACKOFF: u64 = 5000;
|
||||
// If the connection dropped then re-connect more quickly.
|
||||
const RESET_BACKOFF: u64 = 200;
|
||||
// How long to wait for the broker to confirm actions.
|
||||
const CONFIRMATION_TIMEOUT: u64 = 2000;
|
||||
|
||||
static DATA_CHANNEL: Channel<CriticalSectionRawMutex, MqttMessage, 10> = Channel::new();
|
||||
|
||||
static DEVICE_TYPE: OnceCell<String<32>> = OnceCell::new();
|
||||
static DEVICE_ID: OnceCell<String<32>> = OnceCell::new();
|
||||
|
||||
fn device_id() -> &'static str {
|
||||
DEVICE_ID.get().unwrap()
|
||||
}
|
||||
|
||||
fn device_type() -> &'static str {
|
||||
DEVICE_TYPE.get().unwrap()
|
||||
}
|
||||
|
||||
/// Various errors
|
||||
#[derive(Debug, Clone, Copy, PartialEq, Eq)]
|
||||
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
|
||||
pub enum Error {
|
||||
/// An IO error occured.
|
||||
IOError,
|
||||
/// The operation timed out.
|
||||
TimedOut,
|
||||
/// An attempt was made to encode something too large.
|
||||
TooLarge,
|
||||
/// A packet or payload could not be decoded or encoded.
|
||||
PacketError,
|
||||
/// An invalid or unsupported operation was attempted.
|
||||
Invalid,
|
||||
/// A value was rejected.
|
||||
Rejected,
|
||||
}
|
||||
|
||||
#[allow(clippy::large_enum_variant)]
|
||||
/// A message from the MQTT broker.
|
||||
pub enum MqttMessage {
|
||||
/// The broker has been connected to successfully. Generally in response to this message a
|
||||
/// device should subscribe to topics of interest and send out any device state.
|
||||
Connected,
|
||||
/// New data received from the broker.
|
||||
Publish(Topic<TopicString>, Payload),
|
||||
/// The connection to the broker has been dropped.
|
||||
Disconnected,
|
||||
/// Home Assistant has come online and you should send any discovery messages.
|
||||
#[cfg(feature = "homeassistant")]
|
||||
HomeAssistantOnline,
|
||||
}
|
||||
|
||||
#[derive(Clone)]
|
||||
enum ControlMessage {
|
||||
Published(Pid),
|
||||
Subscribed(Pid, SubscribeReturnCodes),
|
||||
Unsubscribed(Pid),
|
||||
}
|
||||
|
||||
/// Receives messages from the broker.
|
||||
pub struct McutieReceiver;
|
||||
|
||||
impl McutieReceiver {
|
||||
/// Waits for the next message from the broker.
|
||||
pub async fn receive(&self) -> MqttMessage {
|
||||
DATA_CHANNEL.receive().await
|
||||
}
|
||||
}
|
||||
|
||||
/// A builder to configure the MQTT stack.
|
||||
pub struct McutieBuilder<'t, T, L, const S: usize>
|
||||
where
|
||||
T: Deref<Target = str> + 't,
|
||||
L: Publishable + 't,
|
||||
{
|
||||
network: Stack<'t>,
|
||||
device_type: &'t str,
|
||||
device_id: Option<&'t str>,
|
||||
broker: &'t str,
|
||||
last_will: Option<L>,
|
||||
username: Option<&'t str>,
|
||||
password: Option<&'t str>,
|
||||
subscriptions: [Topic<T>; S],
|
||||
}
|
||||
|
||||
impl<'t, T: Deref<Target = str> + 't, L: Publishable + 't> McutieBuilder<'t, T, L, 0> {
|
||||
/// Creates a new builder with the initial required configuration.
|
||||
///
|
||||
/// `device_type` is expected to be the same for all devices of the same type.
|
||||
/// `broker` may be an IP address or a DNS name for the broker to connect to.
|
||||
pub fn new(network: Stack<'t>, device_type: &'t str, broker: &'t str) -> Self {
|
||||
Self {
|
||||
network,
|
||||
device_type,
|
||||
broker,
|
||||
device_id: None,
|
||||
last_will: None,
|
||||
username: None,
|
||||
password: None,
|
||||
subscriptions: [],
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'t, T: Deref<Target = str> + 't, L: Publishable + 't, const S: usize>
|
||||
McutieBuilder<'t, T, L, S>
|
||||
{
|
||||
/// Add some default topics to subscribe to.
|
||||
pub fn with_subscriptions<const N: usize>(
|
||||
self,
|
||||
subscriptions: [Topic<T>; N],
|
||||
) -> McutieBuilder<'t, T, L, N> {
|
||||
McutieBuilder {
|
||||
network: self.network,
|
||||
device_type: self.device_type,
|
||||
broker: self.broker,
|
||||
device_id: self.device_id,
|
||||
last_will: self.last_will,
|
||||
username: self.username,
|
||||
password: self.password,
|
||||
subscriptions,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<'t, T: Deref<Target = str> + 't, L: Publishable + 't, const S: usize>
|
||||
McutieBuilder<'t, T, L, S>
|
||||
{
|
||||
/// Adds authentication for the broker.
|
||||
pub fn with_authentication(self, username: &'t str, password: &'t str) -> Self {
|
||||
Self {
|
||||
username: Some(username),
|
||||
password: Some(password),
|
||||
..self
|
||||
}
|
||||
}
|
||||
|
||||
/// Sets a last will message to be published in the event of disconnection.
|
||||
pub fn with_last_will(self, last_will: L) -> Self {
|
||||
Self {
|
||||
last_will: Some(last_will),
|
||||
..self
|
||||
}
|
||||
}
|
||||
|
||||
/// Sets a custom unique device identifier. If none is set then the network
|
||||
/// MAC address is used.
|
||||
pub fn with_device_id(self, device_id: &'t str) -> Self {
|
||||
Self {
|
||||
device_id: Some(device_id),
|
||||
..self
|
||||
}
|
||||
}
|
||||
|
||||
/// Initialises the MQTT stack returning a receiver for listening to
|
||||
/// messages from the broker and a future that must be run in order for the
|
||||
/// stack to operate.
|
||||
pub fn build(self, keep_alive: u16) -> (McutieReceiver, McutieTask<'t, T, L, S>) {
|
||||
let mut dtype = String::<32>::new();
|
||||
dtype.push_str(self.device_type).unwrap();
|
||||
DEVICE_TYPE.set(dtype).unwrap();
|
||||
|
||||
let mut did = String::<32>::new();
|
||||
if let Some(device_id) = self.device_id {
|
||||
did.push_str(device_id).unwrap();
|
||||
} else if let HardwareAddress::Ethernet(address) = self.network.hardware_address() {
|
||||
let mut buffer = [0_u8; 12];
|
||||
hex::encode_to_slice(address.as_bytes(), &mut buffer).unwrap();
|
||||
did.push_str(str::from_utf8(&buffer).unwrap()).unwrap();
|
||||
}
|
||||
|
||||
DEVICE_ID.set(did).unwrap();
|
||||
|
||||
(
|
||||
McutieReceiver {},
|
||||
McutieTask {
|
||||
network: self.network,
|
||||
broker: self.broker,
|
||||
last_will: self.last_will,
|
||||
username: self.username,
|
||||
password: self.password,
|
||||
subscriptions: self.subscriptions,
|
||||
keep_alive
|
||||
},
|
||||
)
|
||||
}
|
||||
}
|
||||
267
rust/src/mcutie_3_0_0/pipe.rs
Normal file
267
rust/src/mcutie_3_0_0/pipe.rs
Normal file
@@ -0,0 +1,267 @@
|
||||
use core::{
|
||||
cell::RefCell,
|
||||
future::Future,
|
||||
pin::Pin,
|
||||
task::{Context, Poll, Waker},
|
||||
};
|
||||
|
||||
use embassy_sync::blocking_mutex::{raw::RawMutex, Mutex};
|
||||
use pin_project::pin_project;
|
||||
|
||||
struct PipeData<T, const N: usize> {
|
||||
connect_count: usize,
|
||||
receiver_waker: Option<Waker>,
|
||||
sender_waker: Option<Waker>,
|
||||
pending: Option<T>,
|
||||
}
|
||||
|
||||
fn swap_wakers(waker: &mut Option<Waker>, new_waker: &Waker) {
|
||||
if let Some(old_waker) = waker.take() {
|
||||
if old_waker.will_wake(new_waker) {
|
||||
*waker = Some(old_waker)
|
||||
} else {
|
||||
if !new_waker.will_wake(&old_waker) {
|
||||
old_waker.wake();
|
||||
}
|
||||
|
||||
*waker = Some(new_waker.clone());
|
||||
}
|
||||
} else {
|
||||
*waker = Some(new_waker.clone())
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) struct ReceiveFuture<'a, M: RawMutex, T, const N: usize> {
|
||||
pipe: &'a ConnectedPipe<M, T, N>,
|
||||
}
|
||||
|
||||
impl<M: RawMutex, T, const N: usize> Future for ReceiveFuture<'_, M, T, N> {
|
||||
type Output = T;
|
||||
|
||||
fn poll(self: Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<Self::Output> {
|
||||
self.pipe.inner.lock(|cell| {
|
||||
let mut inner = cell.borrow_mut();
|
||||
|
||||
if let Some(waker) = inner.sender_waker.take() {
|
||||
waker.wake();
|
||||
}
|
||||
|
||||
if let Some(item) = inner.pending.take() {
|
||||
if let Some(old_waker) = inner.receiver_waker.take() {
|
||||
old_waker.wake();
|
||||
}
|
||||
|
||||
Poll::Ready(item)
|
||||
} else {
|
||||
swap_wakers(&mut inner.receiver_waker, cx.waker());
|
||||
Poll::Pending
|
||||
}
|
||||
})
|
||||
}
|
||||
}
|
||||
|
||||
pub(crate) struct PipeReader<'a, M: RawMutex, T, const N: usize> {
|
||||
pipe: &'a ConnectedPipe<M, T, N>,
|
||||
}
|
||||
|
||||
impl<M: RawMutex, T, const N: usize> PipeReader<'_, M, T, N> {
|
||||
#[must_use]
|
||||
pub(crate) fn receive(&self) -> ReceiveFuture<'_, M, T, N> {
|
||||
ReceiveFuture { pipe: self.pipe }
|
||||
}
|
||||
}
|
||||
|
||||
impl<M: RawMutex, T, const N: usize> Drop for PipeReader<'_, M, T, N> {
|
||||
fn drop(&mut self) {
|
||||
self.pipe.inner.lock(|cell| {
|
||||
let mut inner = cell.borrow_mut();
|
||||
inner.connect_count -= 1;
|
||||
|
||||
if inner.connect_count == 0 {
|
||||
inner.pending = None;
|
||||
}
|
||||
|
||||
if let Some(waker) = inner.sender_waker.take() {
|
||||
waker.wake();
|
||||
}
|
||||
})
|
||||
}
|
||||
}
|
||||
|
||||
#[pin_project]
|
||||
pub(crate) struct PushFuture<'a, M: RawMutex, T, const N: usize> {
|
||||
data: Option<T>,
|
||||
pipe: &'a ConnectedPipe<M, T, N>,
|
||||
}
|
||||
|
||||
impl<M: RawMutex, T, const N: usize> Future for PushFuture<'_, M, T, N> {
|
||||
type Output = ();
|
||||
|
||||
fn poll(self: Pin<&mut Self>, cx: &mut Context<'_>) -> Poll<Self::Output> {
|
||||
self.pipe.inner.lock(|cell| {
|
||||
let project = self.project();
|
||||
let mut inner = cell.borrow_mut();
|
||||
|
||||
if let Some(receiver) = inner.receiver_waker.take() {
|
||||
receiver.wake();
|
||||
}
|
||||
|
||||
if project.data.is_none() || inner.connect_count == 0 {
|
||||
trace!("Dropping packet");
|
||||
Poll::Ready(())
|
||||
} else if inner.pending.is_some() {
|
||||
swap_wakers(&mut inner.sender_waker, cx.waker());
|
||||
Poll::Pending
|
||||
} else {
|
||||
inner.pending = project.data.take();
|
||||
|
||||
Poll::Ready(())
|
||||
}
|
||||
})
|
||||
}
|
||||
}
|
||||
|
||||
/// A pipe that knows whether a receiver is connected. If so pushing to the
|
||||
/// queue waits until there is space in the queue, otherwise data is simply
|
||||
/// dropped.
|
||||
pub(crate) struct ConnectedPipe<M: RawMutex, T, const N: usize> {
|
||||
inner: Mutex<M, RefCell<PipeData<T, N>>>,
|
||||
}
|
||||
|
||||
impl<M: RawMutex, T, const N: usize> ConnectedPipe<M, T, N> {
|
||||
pub(crate) const fn new() -> Self {
|
||||
Self {
|
||||
inner: Mutex::new(RefCell::new(PipeData {
|
||||
connect_count: 0,
|
||||
receiver_waker: None,
|
||||
sender_waker: None,
|
||||
pending: None,
|
||||
})),
|
||||
}
|
||||
}
|
||||
|
||||
/// A future that waits for a new item to be available.
|
||||
pub(crate) fn reader(&self) -> PipeReader<'_, M, T, N> {
|
||||
self.inner.lock(|cell| {
|
||||
let mut inner = cell.borrow_mut();
|
||||
inner.connect_count += 1;
|
||||
|
||||
PipeReader { pipe: self }
|
||||
})
|
||||
}
|
||||
|
||||
/// Pushes an item to the reader, waiting for a slot to become available if
|
||||
/// connected.
|
||||
#[must_use]
|
||||
pub(crate) fn push(&self, data: T) -> PushFuture<'_, M, T, N> {
|
||||
PushFuture {
|
||||
data: Some(data),
|
||||
pipe: self,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(test)]
|
||||
mod tests {
|
||||
use core::time::Duration;
|
||||
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use futures_executor::{LocalPool, ThreadPool};
|
||||
use futures_timer::Delay;
|
||||
use futures_util::{future::select, pin_mut, task::SpawnExt, FutureExt};
|
||||
|
||||
use super::ConnectedPipe;
|
||||
|
||||
async fn wait_milis(milis: u64) {
|
||||
Delay::new(Duration::from_millis(milis)).await;
|
||||
}
|
||||
|
||||
// #[futures_test::test]
|
||||
#[test]
|
||||
fn test_send_receive() {
|
||||
let mut executor = LocalPool::new();
|
||||
let spawner = executor.spawner();
|
||||
|
||||
static PIPE: ConnectedPipe<CriticalSectionRawMutex, usize, 5> = ConnectedPipe::new();
|
||||
|
||||
// Task that sends
|
||||
spawner
|
||||
.spawn(async {
|
||||
wait_milis(10).await;
|
||||
|
||||
PIPE.push(23).await;
|
||||
PIPE.push(56).await;
|
||||
PIPE.push(67).await;
|
||||
})
|
||||
.unwrap();
|
||||
|
||||
// Task that receives
|
||||
spawner
|
||||
.spawn(async {
|
||||
let reader = PIPE.reader();
|
||||
let value = reader.receive().await;
|
||||
assert_eq!(value, 23);
|
||||
let value = reader.receive().await;
|
||||
assert_eq!(value, 56);
|
||||
let value = reader.receive().await;
|
||||
assert_eq!(value, 67);
|
||||
})
|
||||
.unwrap();
|
||||
|
||||
executor.run();
|
||||
}
|
||||
|
||||
#[futures_test::test]
|
||||
async fn test_send_drop() {
|
||||
static PIPE: ConnectedPipe<CriticalSectionRawMutex, usize, 5> = ConnectedPipe::new();
|
||||
|
||||
PIPE.push(23).await;
|
||||
PIPE.push(56).await;
|
||||
PIPE.push(67).await;
|
||||
|
||||
// Create a reader after sending
|
||||
let reader = PIPE.reader();
|
||||
let receive = reader.receive().fuse();
|
||||
pin_mut!(receive);
|
||||
|
||||
let timeout = wait_milis(50).fuse();
|
||||
pin_mut!(timeout);
|
||||
|
||||
let either = select(receive, timeout).await;
|
||||
|
||||
match either {
|
||||
futures_util::future::Either::Left(_) => {
|
||||
panic!("There should be nothing to receive!");
|
||||
}
|
||||
futures_util::future::Either::Right(_) => {}
|
||||
}
|
||||
}
|
||||
|
||||
#[futures_test::test]
|
||||
async fn test_bulk_send_publish() {
|
||||
static PIPE: ConnectedPipe<CriticalSectionRawMutex, usize, 5> = ConnectedPipe::new();
|
||||
|
||||
let executor = ThreadPool::new().unwrap();
|
||||
|
||||
executor
|
||||
.spawn(async {
|
||||
for i in 0..1000 {
|
||||
PIPE.push(i).await;
|
||||
}
|
||||
})
|
||||
.unwrap();
|
||||
|
||||
executor
|
||||
.spawn(async {
|
||||
for i in 1000..2000 {
|
||||
PIPE.push(i).await;
|
||||
}
|
||||
})
|
||||
.unwrap();
|
||||
|
||||
let reader = PIPE.reader();
|
||||
for _ in 0..800 {
|
||||
reader.receive().await;
|
||||
}
|
||||
}
|
||||
}
|
||||
173
rust/src/mcutie_3_0_0/publish.rs
Normal file
173
rust/src/mcutie_3_0_0/publish.rs
Normal file
@@ -0,0 +1,173 @@
|
||||
use core::{fmt::Display, future::Future, ops::Deref};
|
||||
|
||||
use embedded_io::Write;
|
||||
use mqttrs::QoS;
|
||||
|
||||
use crate::{io::publish, Error, Payload, Topic, TopicString};
|
||||
|
||||
/// A message that can be published to an MQTT broker.
|
||||
pub trait Publishable {
|
||||
/// Write this message's topic into the supplied buffer.
|
||||
fn write_topic(&self, buffer: &mut TopicString) -> Result<(), Error>;
|
||||
|
||||
/// Write this message's payload into the supplied buffer.
|
||||
fn write_payload(&self, buffer: &mut Payload) -> Result<(), Error>;
|
||||
|
||||
/// Get this message's QoS level.
|
||||
fn qos(&self) -> QoS {
|
||||
QoS::AtMostOnce
|
||||
}
|
||||
|
||||
/// Whether the broker should retain this message.
|
||||
fn retain(&self) -> bool {
|
||||
false
|
||||
}
|
||||
|
||||
/// Publishes this message to the broker. If the stack has not yet been
|
||||
/// initialized this is likely to panic.
|
||||
fn publish(&self) -> impl Future<Output = Result<(), Error>> {
|
||||
async {
|
||||
let mut topic = TopicString::new();
|
||||
self.write_topic(&mut topic)?;
|
||||
|
||||
let mut payload = Payload::new();
|
||||
self.write_payload(&mut payload)?;
|
||||
|
||||
publish(&topic, &payload, self.qos(), self.retain()).await
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// A [`Publishable`] with a raw byte payload.
|
||||
pub struct PublishBytes<'a, T, B: AsRef<[u8]>> {
|
||||
pub(crate) topic: &'a Topic<T>,
|
||||
pub(crate) data: B,
|
||||
pub(crate) qos: QoS,
|
||||
pub(crate) retain: bool,
|
||||
}
|
||||
|
||||
impl<T, B: AsRef<[u8]>> PublishBytes<'_, T, B> {
|
||||
/// Sets the QoS level for this message.
|
||||
pub fn qos(mut self, qos: QoS) -> Self {
|
||||
self.qos = qos;
|
||||
self
|
||||
}
|
||||
|
||||
/// Sets whether the broker should retain this message.
|
||||
pub fn retain(mut self, retain: bool) -> Self {
|
||||
self.retain = retain;
|
||||
self
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T: Deref<Target = str> + 'a, B: AsRef<[u8]>> Publishable for PublishBytes<'a, T, B> {
|
||||
fn write_topic(&self, buffer: &mut TopicString) -> Result<(), Error> {
|
||||
self.topic.to_string(buffer)
|
||||
}
|
||||
|
||||
fn write_payload(&self, buffer: &mut Payload) -> Result<(), Error> {
|
||||
buffer
|
||||
.write_all(self.data.as_ref())
|
||||
.map_err(|_| Error::TooLarge)
|
||||
}
|
||||
|
||||
fn qos(&self) -> QoS {
|
||||
self.qos
|
||||
}
|
||||
|
||||
fn retain(&self) -> bool {
|
||||
self.retain
|
||||
}
|
||||
|
||||
async fn publish(&self) -> Result<(), Error> {
|
||||
let mut topic = TopicString::new();
|
||||
self.write_topic(&mut topic)?;
|
||||
|
||||
publish(&topic, self.data.as_ref(), self.qos(), self.retain()).await
|
||||
}
|
||||
}
|
||||
|
||||
/// A [`Publishable`] with a payload that implements [`Display`].
|
||||
pub struct PublishDisplay<'a, T, D: Display> {
|
||||
pub(crate) topic: &'a Topic<T>,
|
||||
pub(crate) data: D,
|
||||
pub(crate) qos: QoS,
|
||||
pub(crate) retain: bool,
|
||||
}
|
||||
|
||||
impl<T, D: Display> PublishDisplay<'_, T, D> {
|
||||
/// Sets the QoS level for this message.
|
||||
pub fn qos(mut self, qos: QoS) -> Self {
|
||||
self.qos = qos;
|
||||
self
|
||||
}
|
||||
|
||||
/// Sets whether the broker should retain this message.
|
||||
pub fn retain(mut self, retain: bool) -> Self {
|
||||
self.retain = retain;
|
||||
self
|
||||
}
|
||||
}
|
||||
|
||||
impl<'a, T: Deref<Target = str> + 'a, D: Display> Publishable for PublishDisplay<'a, T, D> {
|
||||
fn write_topic(&self, buffer: &mut TopicString) -> Result<(), Error> {
|
||||
self.topic.to_string(buffer)
|
||||
}
|
||||
|
||||
fn write_payload(&self, buffer: &mut Payload) -> Result<(), Error> {
|
||||
write!(buffer, "{}", self.data).map_err(|_| Error::TooLarge)
|
||||
}
|
||||
|
||||
fn qos(&self) -> QoS {
|
||||
self.qos
|
||||
}
|
||||
|
||||
fn retain(&self) -> bool {
|
||||
self.retain
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
/// A [`Publishable`] with that serializes a JSON payload.
|
||||
pub struct PublishJson<'a, T, D: serde::Serialize> {
|
||||
pub(crate) topic: &'a Topic<T>,
|
||||
pub(crate) data: D,
|
||||
pub(crate) qos: QoS,
|
||||
pub(crate) retain: bool,
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
impl<T, D: serde::Serialize> PublishJson<'_, T, D> {
|
||||
/// Sets the QoS level for this message.
|
||||
pub fn qos(mut self, qos: QoS) -> Self {
|
||||
self.qos = qos;
|
||||
self
|
||||
}
|
||||
|
||||
/// Sets whether the broker should retain this message.
|
||||
pub fn retain(mut self, retain: bool) -> Self {
|
||||
self.retain = retain;
|
||||
self
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
impl<'a, T: Deref<Target = str> + 'a, D: serde::Serialize> Publishable for PublishJson<'a, T, D> {
|
||||
fn write_topic(&self, buffer: &mut TopicString) -> Result<(), Error> {
|
||||
self.topic.to_string(buffer)
|
||||
}
|
||||
|
||||
fn write_payload(&self, buffer: &mut Payload) -> Result<(), Error> {
|
||||
buffer
|
||||
.serialize_json(&self.data)
|
||||
.map_err(|_| Error::TooLarge)
|
||||
}
|
||||
|
||||
fn qos(&self) -> QoS {
|
||||
self.qos
|
||||
}
|
||||
|
||||
fn retain(&self) -> bool {
|
||||
self.retain
|
||||
}
|
||||
}
|
||||
284
rust/src/mcutie_3_0_0/topic.rs
Normal file
284
rust/src/mcutie_3_0_0/topic.rs
Normal file
@@ -0,0 +1,284 @@
|
||||
use core::{fmt::Display, ops::Deref};
|
||||
|
||||
use embassy_futures::select::{select, Either};
|
||||
use embassy_sync::pubsub::WaitResult;
|
||||
use embassy_time::Timer;
|
||||
use heapless::{String, Vec};
|
||||
use mqttrs::{Packet, QoS, Subscribe, SubscribeReturnCodes, SubscribeTopic, Unsubscribe};
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
use crate::publish::PublishJson;
|
||||
use crate::{
|
||||
device_id, device_type,
|
||||
io::{assign_pid, send_packet, subscribe},
|
||||
publish::{PublishBytes, PublishDisplay},
|
||||
ControlMessage, Error, TopicString, CONFIRMATION_TIMEOUT,
|
||||
};
|
||||
|
||||
/// An MQTT topic that is optionally prefixed with the device type and unique ID.
|
||||
/// Normally you will define all your application's topics as consts with static
|
||||
/// lifetimes.
|
||||
///
|
||||
/// A [`Topic`] is the main entry to publishing messages to the broker.
|
||||
///
|
||||
/// ```
|
||||
/// # use mcutie::{Publishable, Topic};
|
||||
/// const DEVICE_AVAILABILITY: Topic<&'static str> = Topic::Device("state");
|
||||
///
|
||||
/// async fn send_status(status: &'static str) {
|
||||
/// let _ = DEVICE_AVAILABILITY.with_bytes(status.as_bytes()).publish().await;
|
||||
/// }
|
||||
/// ```
|
||||
#[derive(Clone, Copy)]
|
||||
pub enum Topic<T> {
|
||||
/// A topic that is prefixed with the device type.
|
||||
DeviceType(T),
|
||||
/// A topic that is prefixed with the device type and unique ID.
|
||||
Device(T),
|
||||
/// Any topic.
|
||||
General(T),
|
||||
}
|
||||
|
||||
impl<A, B> PartialEq<Topic<A>> for Topic<B>
|
||||
where
|
||||
B: PartialEq<A>,
|
||||
{
|
||||
fn eq(&self, other: &Topic<A>) -> bool {
|
||||
match (self, other) {
|
||||
(Topic::DeviceType(l0), Topic::DeviceType(r0)) => l0 == r0,
|
||||
(Topic::Device(l0), Topic::Device(r0)) => l0 == r0,
|
||||
(Topic::General(l0), Topic::General(r0)) => l0 == r0,
|
||||
_ => false,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<T> Topic<T> {
|
||||
/// Creates a publishable message with something that can return a reference
|
||||
/// to the payload in bytes.
|
||||
///
|
||||
/// Defaults to non-retained with QoS of 0 (AtMostOnce).
|
||||
pub fn with_bytes<B: AsRef<[u8]>>(&self, data: B) -> PublishBytes<'_, T, B> {
|
||||
PublishBytes {
|
||||
topic: self,
|
||||
data,
|
||||
qos: QoS::AtMostOnce,
|
||||
retain: false,
|
||||
}
|
||||
}
|
||||
|
||||
/// Creates a publishable message with something that implements [`Display`].
|
||||
///
|
||||
/// Defaults to non-retained with QoS of 0 (AtMostOnce).
|
||||
pub fn with_display<D: Display>(&self, data: D) -> PublishDisplay<'_, T, D> {
|
||||
PublishDisplay {
|
||||
topic: self,
|
||||
data,
|
||||
qos: QoS::AtMostOnce,
|
||||
retain: false,
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(feature = "serde")]
|
||||
/// Creates a publishable message with something that can be serialized to
|
||||
/// JSON.
|
||||
///
|
||||
/// Defaults to non-retained with QoS of 0 (AtMostOnce).
|
||||
pub fn with_json<D: serde::Serialize>(&self, data: D) -> PublishJson<'_, T, D> {
|
||||
PublishJson {
|
||||
topic: self,
|
||||
data,
|
||||
qos: QoS::AtMostOnce,
|
||||
retain: false,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl Topic<TopicString> {
|
||||
pub(crate) fn from_str(mut st: &str) -> Result<Self, Error> {
|
||||
let mut strip_prefix = |pr: &str| -> bool {
|
||||
if st.starts_with(pr) && st.len() > pr.len() && &st[pr.len()..pr.len() + 1] == "/" {
|
||||
st = &st[pr.len() + 1..];
|
||||
true
|
||||
} else {
|
||||
false
|
||||
}
|
||||
};
|
||||
|
||||
if strip_prefix(device_type()) {
|
||||
if strip_prefix(device_id()) {
|
||||
let mut topic = TopicString::new();
|
||||
topic.push_str(st).map_err(|_| Error::TooLarge)?;
|
||||
Ok(Topic::Device(topic))
|
||||
} else {
|
||||
let mut topic = TopicString::new();
|
||||
topic.push_str(st).map_err(|_| Error::TooLarge)?;
|
||||
Ok(Topic::DeviceType(topic))
|
||||
}
|
||||
} else {
|
||||
let mut topic = TopicString::new();
|
||||
topic.push_str(st).map_err(|_| Error::TooLarge)?;
|
||||
Ok(Topic::General(topic))
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
impl<T: Deref<Target = str>> Topic<T> {
|
||||
pub(crate) fn to_string<const N: usize>(&self, result: &mut String<N>) -> Result<(), Error> {
|
||||
match self {
|
||||
Topic::Device(st) => {
|
||||
result
|
||||
.push_str(device_type())
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
result.push_str("/").map_err(|_| Error::TooLarge)?;
|
||||
result.push_str(device_id()).map_err(|_| Error::TooLarge)?;
|
||||
result.push_str("/").map_err(|_| Error::TooLarge)?;
|
||||
result.push_str(st.as_ref()).map_err(|_| Error::TooLarge)?;
|
||||
}
|
||||
Topic::DeviceType(st) => {
|
||||
result
|
||||
.push_str(device_type())
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
result.push_str("/").map_err(|_| Error::TooLarge)?;
|
||||
result.push_str(st.as_ref()).map_err(|_| Error::TooLarge)?;
|
||||
}
|
||||
Topic::General(st) => {
|
||||
result.push_str(st.as_ref()).map_err(|_| Error::TooLarge)?;
|
||||
}
|
||||
}
|
||||
|
||||
Ok(())
|
||||
}
|
||||
|
||||
/// Converts to a topic containing an [`str`]. Particularly useful for converting from an owned
|
||||
/// string for match patterns.
|
||||
pub fn as_ref(&self) -> Topic<&str> {
|
||||
match self {
|
||||
Topic::DeviceType(st) => Topic::DeviceType(st.as_ref()),
|
||||
Topic::Device(st) => Topic::Device(st.as_ref()),
|
||||
Topic::General(st) => Topic::General(st.as_ref()),
|
||||
}
|
||||
}
|
||||
|
||||
/// Subscribes to this topic. If `wait_for_ack` is true then this will wait until confirmation
|
||||
/// is received from the broker before returning.
|
||||
pub async fn subscribe(&self, wait_for_ack: bool) -> Result<(), Error> {
|
||||
let mut subscriber = subscribe().await;
|
||||
|
||||
let mut topic_path = TopicString::new();
|
||||
if self.to_string(&mut topic_path).is_err() {
|
||||
return Err(Error::TooLarge);
|
||||
}
|
||||
|
||||
let pid = assign_pid().await;
|
||||
|
||||
let mut subscribe_topic_path = String::<256>::new();
|
||||
subscribe_topic_path
|
||||
.push_str(topic_path.as_str())
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
let subscribe_topic = SubscribeTopic {
|
||||
topic_path: subscribe_topic_path,
|
||||
qos: QoS::AtLeastOnce,
|
||||
};
|
||||
|
||||
// The size of this vec must match that used by mqttrs.
|
||||
let topics = match Vec::<SubscribeTopic, 5>::from_slice(&[subscribe_topic]) {
|
||||
Ok(t) => t,
|
||||
Err(_) => return Err(Error::TooLarge),
|
||||
};
|
||||
|
||||
let packet = Packet::Subscribe(Subscribe { pid, topics });
|
||||
|
||||
send_packet(packet).await?;
|
||||
|
||||
if wait_for_ack {
|
||||
match select(
|
||||
async {
|
||||
loop {
|
||||
match subscriber.next_message().await {
|
||||
WaitResult::Lagged(_) => {
|
||||
// Maybe we missed the message?
|
||||
}
|
||||
WaitResult::Message(ControlMessage::Subscribed(
|
||||
subscribed_pid,
|
||||
return_code,
|
||||
)) => {
|
||||
if subscribed_pid == pid {
|
||||
if matches!(return_code, SubscribeReturnCodes::Success(_)) {
|
||||
return Ok(());
|
||||
} else {
|
||||
return Err(Error::IOError);
|
||||
}
|
||||
}
|
||||
}
|
||||
_ => {}
|
||||
}
|
||||
}
|
||||
},
|
||||
Timer::after_millis(CONFIRMATION_TIMEOUT),
|
||||
)
|
||||
.await
|
||||
{
|
||||
Either::First(r) => r,
|
||||
Either::Second(_) => Err(Error::TimedOut),
|
||||
}
|
||||
} else {
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
|
||||
/// Unsubscribes from a topic. If `wait_for_ack` is true then this will wait until confirmation is
|
||||
/// received from the broker before returning.
|
||||
pub async fn unsubscribe(&self, wait_for_ack: bool) -> Result<(), Error> {
|
||||
let mut subscriber = subscribe().await;
|
||||
|
||||
let mut topic_path = TopicString::new();
|
||||
if self.to_string(&mut topic_path).is_err() {
|
||||
return Err(Error::TooLarge);
|
||||
}
|
||||
|
||||
let pid = assign_pid().await;
|
||||
|
||||
// The size of this vec must match that used by mqttrs.
|
||||
let mut unsubscribe_topic_path = String::<256>::new();
|
||||
unsubscribe_topic_path
|
||||
.push_str(topic_path.as_str())
|
||||
.map_err(|_| Error::TooLarge)?;
|
||||
let topics = match Vec::<String<256>, 5>::from_slice(&[unsubscribe_topic_path]) {
|
||||
Ok(t) => t,
|
||||
Err(_) => return Err(Error::TooLarge),
|
||||
};
|
||||
|
||||
let packet = Packet::Unsubscribe(Unsubscribe { pid, topics });
|
||||
|
||||
send_packet(packet).await?;
|
||||
|
||||
if wait_for_ack {
|
||||
match select(
|
||||
async {
|
||||
loop {
|
||||
match subscriber.next_message().await {
|
||||
WaitResult::Lagged(_) => {
|
||||
// Maybe we missed the message?
|
||||
}
|
||||
WaitResult::Message(ControlMessage::Unsubscribed(subscribed_pid)) => {
|
||||
if subscribed_pid == pid {
|
||||
return Ok(());
|
||||
}
|
||||
}
|
||||
_ => {}
|
||||
}
|
||||
}
|
||||
},
|
||||
Timer::after_millis(CONFIRMATION_TIMEOUT),
|
||||
)
|
||||
.await
|
||||
{
|
||||
Either::First(r) => r,
|
||||
Either::Second(_) => Err(Error::TimedOut),
|
||||
}
|
||||
} else {
|
||||
Ok(())
|
||||
}
|
||||
}
|
||||
}
|
||||
315
rust/src/mqtt.rs
Normal file
315
rust/src/mqtt.rs
Normal file
@@ -0,0 +1,315 @@
|
||||
use crate::bail;
|
||||
use crate::config::NetworkConfig;
|
||||
use crate::fat_error::{ContextExt, FatError, FatResult};
|
||||
use crate::hal::PlantHal;
|
||||
use crate::log::{log, LogMessage};
|
||||
use alloc::string::String;
|
||||
use alloc::{format, string::ToString, vec::Vec};
|
||||
use core::sync::atomic::Ordering;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_net::Stack;
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::mutex::Mutex;
|
||||
use embassy_sync::once_lock::OnceLock;
|
||||
use embassy_time::{Duration, Timer, WithTimeout};
|
||||
use log::info;
|
||||
use mcutie::{
|
||||
Error, McutieBuilder, McutieReceiver, McutieTask, MqttMessage, PublishDisplay, Publishable,
|
||||
QoS, Topic,
|
||||
};
|
||||
use portable_atomic::AtomicBool;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[derive(Serialize, Deserialize, Debug, PartialEq, Default)]
|
||||
pub struct PumpInfo {
|
||||
pub enabled: bool,
|
||||
pub pump_ineffective: bool,
|
||||
pub median_current_ma: u16,
|
||||
pub max_current_ma: u16,
|
||||
pub min_current_ma: u16,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug, PartialEq)]
|
||||
pub struct Solar {
|
||||
pub current_ma: u32,
|
||||
pub voltage_ma: u32,
|
||||
}
|
||||
|
||||
static MQTT_CONNECTED_EVENT_RECEIVED: AtomicBool = AtomicBool::new(false);
|
||||
static MQTT_ROUND_TRIP_RECEIVED: AtomicBool = AtomicBool::new(false);
|
||||
pub static MQTT_STAY_ALIVE: AtomicBool = AtomicBool::new(false);
|
||||
static MQTT_BASE_TOPIC: OnceLock<String> = OnceLock::new();
|
||||
static MQTT_CONFIG_UPDATE_PAYLOAD: Mutex<CriticalSectionRawMutex, Option<String>> = Mutex::new(None);
|
||||
|
||||
pub fn is_stay_alive() -> bool {
|
||||
MQTT_STAY_ALIVE.load(Ordering::Relaxed)
|
||||
}
|
||||
|
||||
pub async fn publish(subtopic: &str, message: &str) {
|
||||
let online = MQTT_CONNECTED_EVENT_RECEIVED.load(Ordering::Relaxed);
|
||||
if !online {
|
||||
return;
|
||||
}
|
||||
let roundtrip_ok = MQTT_ROUND_TRIP_RECEIVED.load(Ordering::Relaxed);
|
||||
if !roundtrip_ok {
|
||||
info!("MQTT roundtrip not received yet, dropping message");
|
||||
return;
|
||||
}
|
||||
match publish_inner(subtopic, message).await {
|
||||
Ok(()) => {}
|
||||
Err(err) => {
|
||||
info!(
|
||||
"Error during mqtt send on topic {subtopic} with message {message:#?} error is {err:?}"
|
||||
);
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
async fn publish_inner(subtopic: &str, message: &str) -> FatResult<()> {
|
||||
if !subtopic.starts_with("/") {
|
||||
bail!("Subtopic without / at start {}", subtopic);
|
||||
}
|
||||
if subtopic.len() > 192 {
|
||||
bail!("Subtopic exceeds 192 chars {}", subtopic);
|
||||
}
|
||||
let base_topic = MQTT_BASE_TOPIC
|
||||
.try_get()
|
||||
.context("missing base topic in static!")?;
|
||||
|
||||
let full_topic = format!("{base_topic}{subtopic}");
|
||||
|
||||
loop {
|
||||
let result = Topic::General(full_topic.as_str())
|
||||
.with_display(message)
|
||||
.retain(true)
|
||||
.publish()
|
||||
.await;
|
||||
match result {
|
||||
Ok(()) => return Ok(()),
|
||||
Err(err) => {
|
||||
let retry = match err {
|
||||
Error::IOError => false,
|
||||
Error::TimedOut => true,
|
||||
Error::TooLarge => false,
|
||||
Error::PacketError => false,
|
||||
Error::Invalid => false,
|
||||
Error::Rejected => false,
|
||||
};
|
||||
if !retry {
|
||||
bail!(
|
||||
"Error during mqtt send on topic {} with message {:#?} error is {:?}",
|
||||
&full_topic,
|
||||
message,
|
||||
err
|
||||
);
|
||||
}
|
||||
info!(
|
||||
"Retransmit for {} with message {:#?} error is {:?} retrying {}",
|
||||
&full_topic, message, err, retry
|
||||
);
|
||||
Timer::after(Duration::from_millis(100)).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
use crate::util::mk_static;
|
||||
|
||||
pub async fn mqtt_init(
|
||||
network_config: &'static NetworkConfig,
|
||||
stack: Stack<'static>,
|
||||
spawner: Spawner,
|
||||
) -> FatResult<()> {
|
||||
let base_topic = network_config
|
||||
.base_topic
|
||||
.as_ref()
|
||||
.context("missing base topic")?;
|
||||
if base_topic.is_empty() {
|
||||
bail!("Mqtt base_topic was empty")
|
||||
}
|
||||
MQTT_BASE_TOPIC
|
||||
.init(base_topic.to_string())
|
||||
.map_err(|_| FatError::String {
|
||||
error: "Error setting basetopic".to_string(),
|
||||
})?;
|
||||
|
||||
let mqtt_url = network_config
|
||||
.mqtt_url
|
||||
.as_ref()
|
||||
.context("missing mqtt url")?;
|
||||
if mqtt_url.is_empty() {
|
||||
bail!("Mqtt url was empty")
|
||||
}
|
||||
|
||||
let last_will_topic = format!("{base_topic}/state");
|
||||
let round_trip_topic = format!("{base_topic}/internal/roundtrip");
|
||||
let stay_alive_topic = format!("{base_topic}/stay_alive");
|
||||
let config_update_payload_topic = format!("{base_topic}/config/update_payload");
|
||||
let config_update_topic = format!("{base_topic}/config/update");
|
||||
|
||||
let mut builder: McutieBuilder<'_, String, PublishDisplay<String, &str>, 0> =
|
||||
McutieBuilder::new(stack, "plant ctrl", mqtt_url);
|
||||
if let (Some(mqtt_user), Some(mqtt_password)) = (
|
||||
network_config.mqtt_user.as_ref(),
|
||||
network_config.mqtt_password.as_ref(),
|
||||
) {
|
||||
builder = builder.with_authentication(mqtt_user, mqtt_password);
|
||||
info!("With authentification");
|
||||
}
|
||||
|
||||
let lwt = Topic::General(last_will_topic);
|
||||
let lwt = mk_static!(Topic<String>, lwt);
|
||||
let lwt = lwt.with_display("lost").retain(true).qos(QoS::AtLeastOnce);
|
||||
builder = builder.with_last_will(lwt);
|
||||
//TODO make configurable
|
||||
builder = builder.with_device_id("plantctrl");
|
||||
|
||||
let builder: McutieBuilder<'_, String, PublishDisplay<String, &str>, 4> = builder
|
||||
.with_subscriptions([
|
||||
Topic::General(round_trip_topic.clone()),
|
||||
Topic::General(stay_alive_topic.clone()),
|
||||
Topic::General(config_update_payload_topic.clone()),
|
||||
Topic::General(config_update_topic.clone()),
|
||||
]);
|
||||
|
||||
let keep_alive = Duration::from_secs(60 * 60 * 2).as_secs() as u16;
|
||||
let (receiver, task) = builder.build(keep_alive);
|
||||
|
||||
spawner.spawn(mqtt_incoming_task(
|
||||
receiver,
|
||||
round_trip_topic.clone(),
|
||||
stay_alive_topic.clone(),
|
||||
config_update_payload_topic.clone(),
|
||||
config_update_topic.clone(),
|
||||
)?);
|
||||
spawner.spawn(mqtt_runner(task)?);
|
||||
|
||||
log(LogMessage::StayAlive, 0, 0, "", &stay_alive_topic);
|
||||
|
||||
log(LogMessage::MqttInfo, 0, 0, "", mqtt_url);
|
||||
|
||||
let mqtt_timeout = 15000;
|
||||
let res = async {
|
||||
while !MQTT_CONNECTED_EVENT_RECEIVED.load(Ordering::Relaxed) {
|
||||
PlantHal::feed_watchdog();
|
||||
Timer::after(Duration::from_millis(100)).await;
|
||||
}
|
||||
Ok::<(), FatError>(())
|
||||
}
|
||||
.with_timeout(Duration::from_millis(mqtt_timeout as u64))
|
||||
.await;
|
||||
|
||||
if res.is_err() {
|
||||
bail!("Timeout waiting MQTT connect event")
|
||||
}
|
||||
|
||||
let _ = Topic::General(round_trip_topic.clone())
|
||||
.with_display("online_text")
|
||||
.publish()
|
||||
.await;
|
||||
|
||||
let res = async {
|
||||
while !MQTT_ROUND_TRIP_RECEIVED.load(Ordering::Relaxed) {
|
||||
PlantHal::feed_watchdog();
|
||||
Timer::after(Duration::from_millis(100)).await;
|
||||
}
|
||||
Ok::<(), FatError>(())
|
||||
}
|
||||
.with_timeout(Duration::from_millis(mqtt_timeout as u64))
|
||||
.await;
|
||||
|
||||
if res.is_err() {
|
||||
MQTT_CONNECTED_EVENT_RECEIVED.store(false, Ordering::Relaxed);
|
||||
bail!("Timeout waiting MQTT roundtrip")
|
||||
}
|
||||
Ok(())
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn mqtt_runner(
|
||||
task: McutieTask<'static, String, PublishDisplay<'static, String, &'static str>, 4>,
|
||||
) {
|
||||
task.run().await;
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn mqtt_incoming_task(
|
||||
receiver: McutieReceiver,
|
||||
round_trip_topic: String,
|
||||
stay_alive_topic: String,
|
||||
config_update_payload_topic: String,
|
||||
config_update_topic: String,
|
||||
) {
|
||||
loop {
|
||||
let message = receiver.receive().await;
|
||||
match message {
|
||||
MqttMessage::Connected => {
|
||||
info!("Mqtt connected");
|
||||
MQTT_CONNECTED_EVENT_RECEIVED.store(true, Ordering::Relaxed);
|
||||
}
|
||||
MqttMessage::Publish(topic, payload) => match topic {
|
||||
Topic::DeviceType(_type_topic) => {}
|
||||
Topic::Device(_device_topic) => {}
|
||||
Topic::General(topic) => {
|
||||
let subtopic = topic.as_str();
|
||||
|
||||
if subtopic.eq(round_trip_topic.as_str()) {
|
||||
MQTT_ROUND_TRIP_RECEIVED.store(true, Ordering::Relaxed);
|
||||
} else if subtopic.eq(stay_alive_topic.as_str()) {
|
||||
let value = payload.eq_ignore_ascii_case("true".as_ref())
|
||||
|| payload.eq_ignore_ascii_case("1".as_ref());
|
||||
let a = match value {
|
||||
true => 1,
|
||||
false => 0,
|
||||
};
|
||||
log(LogMessage::MqttStayAliveRec, a, 0, "", "");
|
||||
MQTT_STAY_ALIVE.store(value, Ordering::Relaxed);
|
||||
} else if subtopic.eq(config_update_payload_topic.as_str()) {
|
||||
let payload_str = String::from_utf8_lossy(&payload[..]).to_string();
|
||||
let mut buffer = MQTT_CONFIG_UPDATE_PAYLOAD.lock().await;
|
||||
*buffer = Some(payload_str);
|
||||
info!("MQTT config update payload received");
|
||||
} else if subtopic.eq(config_update_topic.as_str()) {
|
||||
let update_requested = payload.eq_ignore_ascii_case("true".as_ref())
|
||||
|| payload.eq_ignore_ascii_case("1".as_ref());
|
||||
if update_requested {
|
||||
info!("MQTT config update requested");
|
||||
let payload_lock = MQTT_CONFIG_UPDATE_PAYLOAD.lock().await;
|
||||
if let Some(payload_str) = payload_lock.as_ref() {
|
||||
match serde_json::from_str::<crate::config::PlantControllerConfig>(payload_str) {
|
||||
Ok(config) => {
|
||||
info!("Deserialized config, applying...");
|
||||
let board_mutex = crate::BOARD_ACCESS.get().await;
|
||||
let mut board = board_mutex.lock().await;
|
||||
if let Err(e) = board.board_hal.get_esp().save_config(payload_str.as_bytes().to_vec()).await {
|
||||
info!("Error saving config to flash: {}", e);
|
||||
let _ = publish("/config/update", "false").await;
|
||||
} else {
|
||||
board.board_hal.set_config(config);
|
||||
info!("Config applied, rebooting");
|
||||
let _ = publish("/config/update", "false").await;
|
||||
board.board_hal.get_esp().deep_sleep_ms(0);
|
||||
}
|
||||
}
|
||||
Err(e) => {
|
||||
info!("Error deserializing config: {}", e);
|
||||
let _ = publish("/config/update", "false").await;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
info!("No config update payload available");
|
||||
let _ = publish("/config/update", "false").await;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
log(LogMessage::UnknownTopic, 0, 0, "", &topic);
|
||||
}
|
||||
}
|
||||
},
|
||||
MqttMessage::Disconnected => {
|
||||
MQTT_CONNECTED_EVENT_RECEIVED.store(false, Ordering::Relaxed);
|
||||
info!("Mqtt disconnected");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
419
rust/src/network.rs
Normal file
419
rust/src/network.rs
Normal file
@@ -0,0 +1,419 @@
|
||||
use crate::bail;
|
||||
use crate::config::NetworkConfig;
|
||||
use crate::fat_error::{ContextExt, FatError, FatResult};
|
||||
use crate::hal::{PlantHal, HAL};
|
||||
use crate::mqtt;
|
||||
use crate::util::mk_static;
|
||||
use alloc::string::{String, ToString};
|
||||
use alloc::sync::Arc;
|
||||
use chrono::{DateTime, Utc};
|
||||
use core::net::{IpAddr, Ipv4Addr, SocketAddr, SocketAddrV4};
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_net::dns::DnsQueryType;
|
||||
use embassy_net::udp::{PacketMetadata, UdpSocket};
|
||||
use embassy_net::{DhcpConfig, Runner, Stack, StackResources, StaticConfigV4};
|
||||
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
|
||||
use embassy_sync::mutex::{Mutex, MutexGuard};
|
||||
use embassy_time::{Duration, Timer, WithTimeout};
|
||||
use option_lock::OptionLock;
|
||||
use edge_dhcp::{
|
||||
io::{self, DEFAULT_SERVER_PORT},
|
||||
server::{Server, ServerOptions},
|
||||
};
|
||||
use edge_nal::UdpBind;
|
||||
use edge_nal_embassy::{Udp, UdpBuffers};
|
||||
use esp_hal::rng::Rng;
|
||||
use esp_println::println;
|
||||
use esp_radio::wifi::ap::AccessPointConfig;
|
||||
use esp_radio::wifi::sta::StationConfig;
|
||||
use esp_radio::wifi::{AuthenticationMethod, Config, Interface};
|
||||
use log::{info, warn, error};
|
||||
use serde::Serialize;
|
||||
use sntpc::{NtpContext, NtpTimestampGenerator, NtpUdpSocket, get_time};
|
||||
|
||||
const NTP_SERVER: &str = "pool.ntp.org";
|
||||
|
||||
#[derive(Copy, Clone, Default)]
|
||||
struct Timestamp {
|
||||
stamp: DateTime<Utc>,
|
||||
}
|
||||
|
||||
impl NtpTimestampGenerator for Timestamp {
|
||||
fn init(&mut self) {
|
||||
self.stamp = DateTime::default();
|
||||
}
|
||||
|
||||
fn timestamp_sec(&self) -> u64 {
|
||||
self.stamp.timestamp() as u64
|
||||
}
|
||||
|
||||
fn timestamp_subsec_micros(&self) -> u32 {
|
||||
self.stamp.timestamp_subsec_micros()
|
||||
}
|
||||
}
|
||||
|
||||
struct EmbassyNtpSocket<'a, 'b> {
|
||||
socket: &'a UdpSocket<'b>,
|
||||
}
|
||||
|
||||
impl<'a, 'b> EmbassyNtpSocket<'a, 'b> {
|
||||
fn new(socket: &'a UdpSocket<'b>) -> Self {
|
||||
Self { socket }
|
||||
}
|
||||
}
|
||||
|
||||
impl NtpUdpSocket for EmbassyNtpSocket<'_, '_> {
|
||||
async fn send_to(&self, buf: &[u8], addr: SocketAddr) -> sntpc::Result<usize> {
|
||||
self.socket
|
||||
.send_to(buf, addr)
|
||||
.await
|
||||
.map_err(|_| sntpc::Error::Network)?;
|
||||
Ok(buf.len())
|
||||
}
|
||||
|
||||
async fn recv_from(&self, buf: &mut [u8]) -> sntpc::Result<(usize, SocketAddr)> {
|
||||
let (len, metadata) = self
|
||||
.socket
|
||||
.recv_from(buf)
|
||||
.await
|
||||
.map_err(|_| sntpc::Error::Network)?;
|
||||
let addr = match metadata.endpoint.addr {
|
||||
embassy_net::IpAddress::Ipv4(ip) => IpAddr::V4(ip),
|
||||
embassy_net::IpAddress::Ipv6(ip) => IpAddr::V6(ip),
|
||||
};
|
||||
Ok((len, SocketAddr::new(addr, metadata.endpoint.port)))
|
||||
}
|
||||
}
|
||||
|
||||
pub async fn sntp(max_wait_ms: u32, stack: Stack<'_>) -> FatResult<DateTime<Utc>> {
|
||||
println!("start sntp");
|
||||
let mut rx_meta = [PacketMetadata::EMPTY; 16];
|
||||
let mut rx_buffer = [0; 4096];
|
||||
let mut tx_meta = [PacketMetadata::EMPTY; 16];
|
||||
let mut tx_buffer = [0; 4096];
|
||||
|
||||
let mut socket = UdpSocket::new(
|
||||
stack,
|
||||
&mut rx_meta,
|
||||
&mut rx_buffer,
|
||||
&mut tx_meta,
|
||||
&mut tx_buffer,
|
||||
);
|
||||
socket.bind(123).context("Could not bind UDP socket")?;
|
||||
|
||||
let context = NtpContext::new(Timestamp::default());
|
||||
let ntp_socket = EmbassyNtpSocket::new(&socket);
|
||||
|
||||
let ntp_addrs = stack
|
||||
.dns_query(NTP_SERVER, DnsQueryType::A)
|
||||
.await
|
||||
.context("Failed to resolve DNS")?;
|
||||
|
||||
if ntp_addrs.is_empty() {
|
||||
bail!("No IP addresses found for NTP server");
|
||||
}
|
||||
let ntp = ntp_addrs[0];
|
||||
info!("NTP server: {ntp:?}");
|
||||
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
let addr: IpAddr = ntp.into();
|
||||
let timeout = get_time(SocketAddr::from((addr, 123)), &ntp_socket, context)
|
||||
.with_timeout(Duration::from_millis((max_wait_ms / 10) as u64))
|
||||
.await;
|
||||
|
||||
match timeout {
|
||||
Ok(result) => {
|
||||
let time = result?;
|
||||
info!("Time: {time:?}");
|
||||
return DateTime::from_timestamp(time.seconds as i64, 0)
|
||||
.context("Could not convert Sntp result");
|
||||
}
|
||||
Err(err) => {
|
||||
warn!("sntp timeout, retry: {err:?}");
|
||||
counter += 1;
|
||||
if counter > 10 {
|
||||
bail!("Failed to get time from NTP server");
|
||||
}
|
||||
Timer::after(Duration::from_millis(100)).await;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug, PartialEq)]
|
||||
pub enum SntpMode {
|
||||
OFFLINE,
|
||||
SYNC { current: DateTime<Utc> },
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug, PartialEq)]
|
||||
pub enum NetworkMode {
|
||||
WIFI {
|
||||
sntp: SntpMode,
|
||||
mqtt: bool,
|
||||
ip_address: String,
|
||||
},
|
||||
OFFLINE,
|
||||
}
|
||||
|
||||
#[embassy_executor::task(pool_size = 2)]
|
||||
pub(crate) async fn net_task(mut runner: Runner<'static, Interface<'static>>) {
|
||||
runner.run().await;
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub(crate) async fn run_dhcp(stack: Stack<'static>, ip: Ipv4Addr) {
|
||||
let mut buf = [0u8; 1500];
|
||||
|
||||
let mut gw_buf = [Ipv4Addr::UNSPECIFIED];
|
||||
|
||||
let buffers = UdpBuffers::<3, 1024, 1024, 10>::new();
|
||||
let unbound_socket = Udp::new(stack, &buffers);
|
||||
let mut bound_socket = match unbound_socket
|
||||
.bind(SocketAddr::V4(SocketAddrV4::new(
|
||||
Ipv4Addr::UNSPECIFIED,
|
||||
DEFAULT_SERVER_PORT,
|
||||
)))
|
||||
.await
|
||||
{
|
||||
Ok(s) => s,
|
||||
Err(e) => {
|
||||
error!("dhcp task failed to bind socket: {:?}", e);
|
||||
return;
|
||||
}
|
||||
};
|
||||
|
||||
loop {
|
||||
_ = io::server::run(
|
||||
&mut Server::<_, 64>::new_with_et(ip),
|
||||
&ServerOptions::new(ip, Some(&mut gw_buf)),
|
||||
&mut bound_socket,
|
||||
&mut buf,
|
||||
)
|
||||
.await
|
||||
.inspect_err(|e| warn!("DHCP server error: {e:?}"));
|
||||
Timer::after(Duration::from_millis(500)).await;
|
||||
}
|
||||
}
|
||||
|
||||
pub async fn wifi_ap(
|
||||
ssid: String,
|
||||
interface_ap: Interface<'static>,
|
||||
controller: &Arc<Mutex<CriticalSectionRawMutex, esp_radio::wifi::WifiController<'static>>>,
|
||||
rng: &mut Rng,
|
||||
spawner: Spawner,
|
||||
) -> FatResult<Stack<'static>> {
|
||||
let gw_ip_addr = Ipv4Addr::new(192, 168, 71, 1);
|
||||
|
||||
let config = embassy_net::Config::ipv4_static(StaticConfigV4 {
|
||||
address: embassy_net::Ipv4Cidr::new(gw_ip_addr, 24),
|
||||
gateway: Some(gw_ip_addr),
|
||||
dns_servers: Default::default(),
|
||||
});
|
||||
|
||||
let seed = (rng.random() as u64) << 32 | rng.random() as u64;
|
||||
|
||||
println!("init secondary stack");
|
||||
let (stack, runner) = embassy_net::new(
|
||||
interface_ap,
|
||||
config,
|
||||
mk_static!(StackResources<4>, StackResources::<4>::new()),
|
||||
seed,
|
||||
);
|
||||
let stack = mk_static!(Stack, stack);
|
||||
|
||||
let client_config =
|
||||
Config::AccessPoint(AccessPointConfig::default().with_ssid(ssid.clone()));
|
||||
controller.lock().await.set_config(&client_config)?;
|
||||
|
||||
println!("start net task");
|
||||
spawner.spawn(net_task(runner)?);
|
||||
println!("run dhcp");
|
||||
spawner.spawn(run_dhcp(*stack, gw_ip_addr)?);
|
||||
|
||||
loop {
|
||||
if stack.is_link_up() {
|
||||
break;
|
||||
}
|
||||
Timer::after(Duration::from_millis(500)).await;
|
||||
}
|
||||
while !stack.is_config_up() {
|
||||
Timer::after(Duration::from_millis(100)).await
|
||||
}
|
||||
println!("Connect to the AP `${ssid}` and point your browser to http://{gw_ip_addr}/");
|
||||
stack
|
||||
.config_v4()
|
||||
.inspect(|c| println!("ipv4 config: {c:?}"));
|
||||
|
||||
Ok(*stack)
|
||||
}
|
||||
|
||||
pub async fn wifi(
|
||||
network_config: &NetworkConfig,
|
||||
interface_sta: Interface<'static>,
|
||||
controller: &Arc<Mutex<CriticalSectionRawMutex, esp_radio::wifi::WifiController<'static>>>,
|
||||
rng: &mut Rng,
|
||||
spawner: Spawner,
|
||||
) -> FatResult<Stack<'static>> {
|
||||
esp_radio::wifi_set_log_verbose();
|
||||
let ssid = match &network_config.ssid {
|
||||
Some(ssid) => {
|
||||
if ssid.is_empty() {
|
||||
bail!("Wifi ssid was empty")
|
||||
}
|
||||
ssid.as_str().to_string()
|
||||
}
|
||||
None => {
|
||||
bail!("Wifi ssid was empty")
|
||||
}
|
||||
};
|
||||
info!("attempting to connect wifi {ssid}");
|
||||
let password = match network_config.password {
|
||||
Some(ref password) => password.as_str().to_string(),
|
||||
None => "".to_string(),
|
||||
};
|
||||
let max_wait = network_config.max_wait;
|
||||
|
||||
let config = embassy_net::Config::dhcpv4(DhcpConfig::default());
|
||||
|
||||
let seed = (rng.random() as u64) << 32 | rng.random() as u64;
|
||||
|
||||
let (stack, runner) = embassy_net::new(
|
||||
interface_sta,
|
||||
config,
|
||||
mk_static!(StackResources<8>, StackResources::<8>::new()),
|
||||
seed,
|
||||
);
|
||||
let stack = mk_static!(Stack, stack);
|
||||
|
||||
let auth_method = if password.is_empty() {
|
||||
AuthenticationMethod::None
|
||||
} else {
|
||||
AuthenticationMethod::Wpa2Personal
|
||||
};
|
||||
let client_config = StationConfig::default()
|
||||
.with_ssid(ssid)
|
||||
.with_auth_method(auth_method)
|
||||
.with_scan_method(esp_radio::wifi::sta::ScanMethod::AllChannels)
|
||||
.with_listen_interval(10)
|
||||
.with_beacon_timeout(10)
|
||||
.with_failure_retry_cnt(3)
|
||||
.with_password(password);
|
||||
|
||||
controller
|
||||
.lock()
|
||||
.await
|
||||
.set_config(&Config::Station(client_config))?;
|
||||
spawner.spawn(net_task(runner)?);
|
||||
controller
|
||||
.lock()
|
||||
.await
|
||||
.connect_async()
|
||||
.with_timeout(Duration::from_millis(max_wait as u64 * 1000))
|
||||
.await
|
||||
.context("Timeout waiting for wifi sta connected")??;
|
||||
|
||||
let res = async {
|
||||
while !stack.is_link_up() {
|
||||
Timer::after(Duration::from_millis(500)).await;
|
||||
}
|
||||
Ok::<(), FatError>(())
|
||||
}
|
||||
.with_timeout(Duration::from_millis(max_wait as u64 * 1000))
|
||||
.await;
|
||||
|
||||
if res.is_err() {
|
||||
bail!("Timeout waiting for wifi link up")
|
||||
}
|
||||
|
||||
let res = async {
|
||||
while !stack.is_config_up() {
|
||||
Timer::after(Duration::from_millis(100)).await
|
||||
}
|
||||
Ok::<(), FatError>(())
|
||||
}
|
||||
.with_timeout(Duration::from_millis(max_wait as u64 * 1000))
|
||||
.await;
|
||||
|
||||
if res.is_err() {
|
||||
bail!("Timeout waiting for wifi config up")
|
||||
}
|
||||
|
||||
info!("Connected WIFI, dhcp: {:?}", stack.config_v4());
|
||||
Ok(*stack)
|
||||
}
|
||||
|
||||
pub async fn try_connect_wifi_sntp_mqtt(
|
||||
board: &mut MutexGuard<'static, CriticalSectionRawMutex, HAL<'static>>,
|
||||
stack_store: &mut OptionLock<Stack<'static>>,
|
||||
spawner: Spawner,
|
||||
) -> NetworkMode {
|
||||
let nw_conf = &board.board_hal.get_config().network.clone();
|
||||
let esp = board.board_hal.get_esp();
|
||||
let device = match esp.interface_sta.take() {
|
||||
Some(d) => d,
|
||||
None => {
|
||||
info!("Offline mode due to STA interface already taken");
|
||||
board.board_hal.general_fault(true).await;
|
||||
return NetworkMode::OFFLINE;
|
||||
}
|
||||
};
|
||||
match wifi(nw_conf, device, &esp.controller, &mut esp.rng, spawner).await {
|
||||
Ok(stack) => {
|
||||
stack_store.replace(stack);
|
||||
|
||||
let sntp_mode: SntpMode = match sntp(1000 * 10, stack).await {
|
||||
Ok(new_time) => {
|
||||
info!("Using time from sntp {}", new_time.to_rfc3339());
|
||||
let _ = board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.set_rtc_time(&new_time)
|
||||
.await;
|
||||
SntpMode::SYNC { current: new_time }
|
||||
}
|
||||
Err(err) => {
|
||||
warn!("sntp error: {err}");
|
||||
board.board_hal.general_fault(true).await;
|
||||
SntpMode::OFFLINE
|
||||
}
|
||||
};
|
||||
|
||||
let mqtt_connected = if board.board_hal.get_config().network.mqtt_url.is_some() {
|
||||
let nw_config = board.board_hal.get_config().network.clone();
|
||||
let nw_config = mk_static!(NetworkConfig, nw_config);
|
||||
match mqtt::mqtt_init(nw_config, stack, spawner).await {
|
||||
Ok(_) => {
|
||||
info!("Mqtt connection ready");
|
||||
true
|
||||
}
|
||||
Err(err) => {
|
||||
warn!("Could not connect mqtt due to {err}");
|
||||
false
|
||||
}
|
||||
}
|
||||
} else {
|
||||
false
|
||||
};
|
||||
|
||||
let ip = match stack.config_v4() {
|
||||
Some(config) => config.address.address().to_string(),
|
||||
None => match stack.config_v6() {
|
||||
Some(config) => config.address.address().to_string(),
|
||||
None => String::from("No IP"),
|
||||
},
|
||||
};
|
||||
NetworkMode::WIFI {
|
||||
sntp: sntp_mode,
|
||||
mqtt: mqtt_connected,
|
||||
ip_address: ip,
|
||||
}
|
||||
}
|
||||
Err(err) => {
|
||||
info!("Offline mode due to {err}");
|
||||
board.board_hal.general_fault(true).await;
|
||||
NetworkMode::OFFLINE
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -118,7 +118,11 @@ fn map_range_moisture(
|
||||
impl PlantState {
|
||||
pub async fn read_hardware_state(plant_id: usize, board: &mut HAL<'_>) -> Self {
|
||||
let sensor_a = if board.board_hal.get_config().plants[plant_id].sensor_a {
|
||||
match board.board_hal.measure_moisture_hz(plant_id, Sensor::A).await {
|
||||
match board
|
||||
.board_hal
|
||||
.measure_moisture_hz(plant_id, Sensor::A)
|
||||
.await
|
||||
{
|
||||
Ok(raw) => match map_range_moisture(
|
||||
raw,
|
||||
board.board_hal.get_config().plants[plant_id].moisture_sensor_min_frequency,
|
||||
@@ -139,7 +143,11 @@ impl PlantState {
|
||||
};
|
||||
|
||||
let sensor_b = if board.board_hal.get_config().plants[plant_id].sensor_b {
|
||||
match board.board_hal.measure_moisture_hz(plant_id, Sensor::B).await {
|
||||
match board
|
||||
.board_hal
|
||||
.measure_moisture_hz(plant_id, Sensor::B)
|
||||
.await
|
||||
{
|
||||
Ok(raw) => match map_range_moisture(
|
||||
raw,
|
||||
board.board_hal.get_config().plants[plant_id].moisture_sensor_min_frequency,
|
||||
@@ -264,50 +272,50 @@ impl PlantState {
|
||||
PlantWateringMode::TimerOnly => !self.pump_in_timeout(plant_conf, current_time),
|
||||
}
|
||||
}
|
||||
//
|
||||
// pub fn to_mqtt_info(
|
||||
// &self,
|
||||
// plant_conf: &PlantConfig,
|
||||
// current_time: &DateTime<Tz>,
|
||||
// ) -> PlantInfo<'_> {
|
||||
// PlantInfo {
|
||||
// sensor_a: &self.sensor_a,
|
||||
// sensor_b: &self.sensor_b,
|
||||
// mode: plant_conf.mode,
|
||||
// do_water: self.needs_to_be_watered(plant_conf, current_time),
|
||||
// dry: if let Some(moisture_percent) = self.plant_moisture().0 {
|
||||
// moisture_percent < plant_conf.target_moisture
|
||||
// } else {
|
||||
// false
|
||||
// },
|
||||
// cooldown: self.pump_in_timeout(plant_conf, current_time),
|
||||
// out_of_work_hour: in_time_range(
|
||||
// current_time,
|
||||
// plant_conf.pump_hour_start,
|
||||
// plant_conf.pump_hour_end,
|
||||
// ),
|
||||
// consecutive_pump_count: self.pump.consecutive_pump_count,
|
||||
// pump_error: self.pump.is_err(plant_conf),
|
||||
// last_pump: self
|
||||
// .pump
|
||||
// .previous_pump
|
||||
// .map(|t| t.with_timezone(¤t_time.timezone())),
|
||||
// next_pump: if matches!(
|
||||
// plant_conf.mode,
|
||||
// PlantWateringMode::TimerOnly
|
||||
// | PlantWateringMode::TargetMoisture
|
||||
// | PlantWateringMode::MinMoisture
|
||||
// ) {
|
||||
// self.pump.previous_pump.and_then(|last_pump| {
|
||||
// last_pump
|
||||
// .checked_add_signed(TimeDelta::minutes(plant_conf.pump_cooldown_min.into()))
|
||||
// .map(|t| t.with_timezone(¤t_time.timezone()))
|
||||
// })
|
||||
// } else {
|
||||
// None
|
||||
// },
|
||||
// }
|
||||
// }
|
||||
|
||||
pub fn to_mqtt_info(
|
||||
&self,
|
||||
plant_conf: &PlantConfig,
|
||||
current_time: &DateTime<Tz>,
|
||||
) -> PlantInfo<'_> {
|
||||
PlantInfo {
|
||||
sensor_a: &self.sensor_a,
|
||||
sensor_b: &self.sensor_b,
|
||||
mode: plant_conf.mode,
|
||||
do_water: self.needs_to_be_watered(plant_conf, current_time),
|
||||
dry: if let Some(moisture_percent) = self.plant_moisture().0 {
|
||||
moisture_percent < plant_conf.target_moisture
|
||||
} else {
|
||||
false
|
||||
},
|
||||
cooldown: self.pump_in_timeout(plant_conf, current_time),
|
||||
out_of_work_hour: in_time_range(
|
||||
current_time,
|
||||
plant_conf.pump_hour_start,
|
||||
plant_conf.pump_hour_end,
|
||||
),
|
||||
consecutive_pump_count: self.pump.consecutive_pump_count,
|
||||
pump_error: self.pump.is_err(plant_conf),
|
||||
last_pump: self
|
||||
.pump
|
||||
.previous_pump
|
||||
.map(|t| t.with_timezone(¤t_time.timezone())),
|
||||
next_pump: if matches!(
|
||||
plant_conf.mode,
|
||||
PlantWateringMode::TimerOnly
|
||||
| PlantWateringMode::TargetMoisture
|
||||
| PlantWateringMode::MinMoisture
|
||||
) {
|
||||
self.pump.previous_pump.and_then(|last_pump| {
|
||||
last_pump
|
||||
.checked_add_signed(TimeDelta::minutes(plant_conf.pump_cooldown_min.into()))
|
||||
.map(|t| t.with_timezone(¤t_time.timezone()))
|
||||
})
|
||||
} else {
|
||||
None
|
||||
},
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[derive(Debug, PartialEq, Serialize)]
|
||||
@@ -330,8 +338,8 @@ pub struct PlantInfo<'a> {
|
||||
/// how often has the pump been watered without reaching target moisture
|
||||
consecutive_pump_count: u32,
|
||||
pump_error: Option<PumpError>,
|
||||
// /// last time when the pump was active
|
||||
// last_pump: Option<DateTime<Tz>>,
|
||||
// /// next time when pump should activate
|
||||
// next_pump: Option<DateTime<Tz>>,
|
||||
/// last time when the pump was active
|
||||
last_pump: Option<DateTime<Tz>>,
|
||||
/// next time when pump should activate
|
||||
next_pump: Option<DateTime<Tz>>,
|
||||
}
|
||||
|
||||
10
rust/src/util.rs
Normal file
10
rust/src/util.rs
Normal file
@@ -0,0 +1,10 @@
|
||||
macro_rules! mk_static {
|
||||
($t:ty,$val:expr) => {{
|
||||
static STATIC_CELL: static_cell::StaticCell<$t> = static_cell::StaticCell::new();
|
||||
#[deny(unused_attributes)]
|
||||
let x = STATIC_CELL.uninit().write(($val));
|
||||
x
|
||||
}};
|
||||
}
|
||||
|
||||
pub(crate) use mk_static;
|
||||
191
rust/src/webserver/backup_manager.rs
Normal file
191
rust/src/webserver/backup_manager.rs
Normal file
@@ -0,0 +1,191 @@
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::rtc::X25;
|
||||
use crate::BOARD_ACCESS;
|
||||
use alloc::borrow::ToOwned;
|
||||
use alloc::format;
|
||||
use alloc::string::{String, ToString};
|
||||
use chrono::DateTime;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_nal::io::{Read, Write};
|
||||
use log::info;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[derive(Serialize, Deserialize, PartialEq, Debug)]
|
||||
pub struct WebBackupHeader {
|
||||
timestamp: String,
|
||||
size: u16,
|
||||
}
|
||||
pub(crate) async fn get_backup_config<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
) -> FatResult<Option<u32>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
// First pass: verify checksum without sending data
|
||||
let mut checksum = X25.digest();
|
||||
let mut chunk = 0_usize;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
let (buf, len, expected_crc) = board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.get_backup_config(chunk)
|
||||
.await?;
|
||||
|
||||
// Update checksum with the actual data bytes of this chunk
|
||||
checksum.update(&buf[..len]);
|
||||
|
||||
let is_last = len == 0 || len < buf.len();
|
||||
if is_last {
|
||||
let actual_crc = checksum.finalize();
|
||||
if actual_crc != expected_crc {
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
conn.initiate_response(
|
||||
409,
|
||||
Some(
|
||||
format!(
|
||||
"Checksum mismatch expected {} got {}",
|
||||
expected_crc, actual_crc
|
||||
)
|
||||
.as_str(),
|
||||
),
|
||||
&[],
|
||||
)
|
||||
.await?;
|
||||
return Ok(Some(409));
|
||||
}
|
||||
break;
|
||||
}
|
||||
chunk += 1;
|
||||
}
|
||||
// Second pass: stream data
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
|
||||
let mut chunk = 0_usize;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
let (buf, len, _expected_crc) = board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.get_backup_config(chunk)
|
||||
.await?;
|
||||
|
||||
if len == 0 {
|
||||
break;
|
||||
}
|
||||
|
||||
conn.write_all(&buf[..len]).await?;
|
||||
|
||||
if len < buf.len() {
|
||||
break;
|
||||
}
|
||||
chunk += 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
Ok(Some(200))
|
||||
}
|
||||
|
||||
pub(crate) async fn backup_config<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut offset = 0_usize;
|
||||
let mut buf = [0_u8; 32];
|
||||
|
||||
let mut checksum = X25.digest();
|
||||
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
let to_write = conn.read(&mut buf).await?;
|
||||
if to_write == 0 {
|
||||
info!("backup finished");
|
||||
break;
|
||||
} else {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(counter).await;
|
||||
|
||||
counter = counter + 1;
|
||||
board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.backup_config(offset, &buf[0..to_write])
|
||||
.await?;
|
||||
checksum.update(&buf[0..to_write]);
|
||||
}
|
||||
offset = offset + to_write;
|
||||
}
|
||||
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.backup_config_finalize(checksum.finalize(), offset)
|
||||
.await?;
|
||||
board.board_hal.clear_progress().await;
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
Ok(Some("saved".to_owned()))
|
||||
}
|
||||
|
||||
pub(crate) async fn backup_info<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> Result<Option<String>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let header = board.board_hal.get_rtc_module().get_backup_info().await;
|
||||
let json = match header {
|
||||
Ok(h) => {
|
||||
let timestamp = DateTime::from_timestamp_millis(h.timestamp).unwrap();
|
||||
let wbh = WebBackupHeader {
|
||||
timestamp: timestamp.to_rfc3339(),
|
||||
size: h.size,
|
||||
};
|
||||
serde_json::to_string(&wbh)?
|
||||
}
|
||||
Err(err) => {
|
||||
let wbh = WebBackupHeader {
|
||||
timestamp: err.to_string(),
|
||||
size: 0,
|
||||
};
|
||||
serde_json::to_string(&wbh)?
|
||||
}
|
||||
};
|
||||
Ok(Some(json))
|
||||
}
|
||||
160
rust/src/webserver/file_manager.rs
Normal file
160
rust/src/webserver/file_manager.rs
Normal file
@@ -0,0 +1,160 @@
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::BOARD_ACCESS;
|
||||
use alloc::borrow::ToOwned;
|
||||
use alloc::format;
|
||||
use alloc::string::String;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_http::Method;
|
||||
use edge_nal::io::{Read, Write};
|
||||
use log::info;
|
||||
|
||||
pub(crate) async fn list_files<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let result = board.board_hal.get_esp().list_files().await?;
|
||||
let file_list_json = serde_json::to_string(&result)?;
|
||||
Ok(Some(file_list_json))
|
||||
}
|
||||
pub(crate) async fn file_operations<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
method: Method,
|
||||
path: &&str,
|
||||
prefix: &&str,
|
||||
) -> Result<Option<u32>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let filename = &path[prefix.len()..];
|
||||
info!("file request for {} with method {}", filename, method);
|
||||
Ok(match method {
|
||||
Method::Delete => {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.delete_file(filename.to_owned())
|
||||
.await?;
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
Some(200)
|
||||
}
|
||||
Method::Get => {
|
||||
let disposition = format!("attachment; filename=\"{filename}\"");
|
||||
let size = {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.get_size(filename.to_owned())
|
||||
.await?
|
||||
};
|
||||
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Content-Type", "application/octet-stream"),
|
||||
("Content-Disposition", disposition.as_str()),
|
||||
("Content-Length", &format!("{}", size)),
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
|
||||
let mut chunk = 0;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk).await;
|
||||
let read_chunk = board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.get_file(filename.to_owned(), chunk)
|
||||
.await?;
|
||||
let length = read_chunk.1;
|
||||
if length == 0 {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
}
|
||||
let data = &read_chunk.0[0..length];
|
||||
conn.write_all(data).await?;
|
||||
if length < read_chunk.0.len() {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
}
|
||||
chunk = chunk + 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
Some(200)
|
||||
}
|
||||
Method::Post => {
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
//ensure the file is deleted first; otherwise we would need to truncate the file which will not work with streaming
|
||||
let _ = board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.delete_file(filename.to_owned())
|
||||
.await;
|
||||
}
|
||||
|
||||
let mut offset = 0_usize;
|
||||
let mut chunk = 0;
|
||||
loop {
|
||||
let mut buf = [0_u8; 1024];
|
||||
let to_write = conn.read(&mut buf).await?;
|
||||
if to_write == 0 {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
} else {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.write_file(filename.to_owned(), offset as u32, &buf[0..to_write])
|
||||
.await?;
|
||||
}
|
||||
offset = offset + to_write;
|
||||
chunk = chunk + 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
Some(200)
|
||||
}
|
||||
_ => None,
|
||||
})
|
||||
}
|
||||
184
rust/src/webserver/get_json.rs
Normal file
184
rust/src/webserver/get_json.rs
Normal file
@@ -0,0 +1,184 @@
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::hal::PLANT_COUNT;
|
||||
use crate::log::LogMessage;
|
||||
use crate::plant_state::{MoistureSensorState, PlantState};
|
||||
use crate::tank::determine_tank_state;
|
||||
use crate::{get_version, BOARD_ACCESS};
|
||||
use alloc::format;
|
||||
use alloc::string::{String, ToString};
|
||||
use alloc::vec::Vec;
|
||||
use chrono_tz::Tz;
|
||||
use core::str::FromStr;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_nal::io::{Read, Write};
|
||||
use log::info;
|
||||
use serde::Serialize;
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
struct LoadData<'a> {
|
||||
rtc: &'a str,
|
||||
native: &'a str,
|
||||
}
|
||||
#[derive(Serialize, Debug)]
|
||||
struct Moistures {
|
||||
moisture_a: Vec<String>,
|
||||
moisture_b: Vec<String>,
|
||||
}
|
||||
#[derive(Serialize, Debug)]
|
||||
struct SolarState {
|
||||
mppt_voltage: f32,
|
||||
mppt_current: f32,
|
||||
is_day: bool,
|
||||
}
|
||||
pub(crate) async fn get_live_moisture<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let mut plant_state = Vec::new();
|
||||
for i in 0..PLANT_COUNT {
|
||||
plant_state.push(PlantState::read_hardware_state(i, &mut board).await);
|
||||
}
|
||||
let a = Vec::from_iter(plant_state.iter().map(|s| match &s.sensor_a {
|
||||
MoistureSensorState::Disabled => "disabled".to_string(),
|
||||
MoistureSensorState::MoistureValue {
|
||||
raw_hz,
|
||||
moisture_percent,
|
||||
} => {
|
||||
format!("{moisture_percent:.2}% {raw_hz}hz",)
|
||||
}
|
||||
MoistureSensorState::SensorError(err) => format!("{err:?}"),
|
||||
}));
|
||||
let b = Vec::from_iter(plant_state.iter().map(|s| match &s.sensor_b {
|
||||
MoistureSensorState::Disabled => "disabled".to_string(),
|
||||
MoistureSensorState::MoistureValue {
|
||||
raw_hz,
|
||||
moisture_percent,
|
||||
} => {
|
||||
format!("{moisture_percent:.2}% {raw_hz}hz",)
|
||||
}
|
||||
MoistureSensorState::SensorError(err) => format!("{err:?}"),
|
||||
}));
|
||||
|
||||
let data = Moistures {
|
||||
moisture_a: a,
|
||||
moisture_b: b,
|
||||
};
|
||||
let json = serde_json::to_string(&data)?;
|
||||
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
pub(crate) async fn tank_info<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> Result<Option<String>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let tank_state = determine_tank_state(&mut board).await;
|
||||
//should be multisampled
|
||||
let sensor = board.board_hal.get_tank_sensor()?;
|
||||
|
||||
let water_temp: FatResult<f32> = sensor.water_temperature_c().await;
|
||||
Ok(Some(serde_json::to_string(&tank_state.as_mqtt_info(
|
||||
&board.board_hal.get_config().tank,
|
||||
&water_temp,
|
||||
))?))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_timezones() -> FatResult<Option<String>> {
|
||||
// Get all timezones compiled into the binary from chrono-tz
|
||||
let timezones: Vec<&'static str> = chrono_tz::TZ_VARIANTS.iter().map(|tz| tz.name()).collect();
|
||||
let json = serde_json::to_string(&timezones)?;
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_solar_state<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let state = SolarState {
|
||||
mppt_voltage: board.board_hal.get_mptt_voltage().await?.as_millivolts() as f32,
|
||||
mppt_current: board.board_hal.get_mptt_current().await?.as_milliamperes() as f32,
|
||||
is_day: board.board_hal.is_day(),
|
||||
};
|
||||
Ok(Some(serde_json::to_string(&state)?))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_version_web<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
Ok(Some(serde_json::to_string(&get_version(&mut board).await)?))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_config<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let json = serde_json::to_string(&board.board_hal.get_config())?;
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_battery_state<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let battery_state = board
|
||||
.board_hal
|
||||
.get_battery_monitor()
|
||||
.get_battery_state()
|
||||
.await?;
|
||||
Ok(Some(serde_json::to_string(&battery_state)?))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_time<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let conf = board.board_hal.get_config();
|
||||
|
||||
let tz: Tz = match conf.timezone.as_ref() {
|
||||
None => Tz::UTC,
|
||||
Some(tz_string) => match Tz::from_str(tz_string) {
|
||||
Ok(tz) => tz,
|
||||
Err(err) => {
|
||||
info!("failed parsing timezone {err}");
|
||||
Tz::UTC
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
let native = board
|
||||
.board_hal
|
||||
.get_time()
|
||||
.await
|
||||
.with_timezone(&tz)
|
||||
.to_rfc3339();
|
||||
|
||||
let rtc = match board.board_hal.get_rtc_module().get_rtc_time().await {
|
||||
Ok(time) => time.with_timezone(&tz).to_rfc3339(),
|
||||
Err(err) => {
|
||||
format!("Error getting time: {err}")
|
||||
}
|
||||
};
|
||||
|
||||
let data = LoadData {
|
||||
rtc: rtc.as_str(),
|
||||
native: native.as_str(),
|
||||
};
|
||||
let json = serde_json::to_string(&data)?;
|
||||
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
pub(crate) async fn get_log_localization_config<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
Ok(Some(serde_json::to_string(
|
||||
&LogMessage::log_localisation_config(),
|
||||
)?))
|
||||
}
|
||||
36
rust/src/webserver/get_log.rs
Normal file
36
rust/src/webserver/get_log.rs
Normal file
@@ -0,0 +1,36 @@
|
||||
use crate::fat_error::FatResult;
|
||||
use crate::log::LOG_ACCESS;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_nal::io::{Read, Write};
|
||||
|
||||
pub(crate) async fn get_log<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<u32>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let log = LOG_ACCESS.lock().await.get();
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Content-Type", "text/javascript"),
|
||||
("Access-Control-Allow-Origin", "*"),
|
||||
("Access-Control-Allow-Headers", "*"),
|
||||
("Access-Control-Allow-Methods", "*"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all("[".as_bytes()).await?;
|
||||
let mut append = false;
|
||||
for entry in log {
|
||||
if append {
|
||||
conn.write_all(",".as_bytes()).await?;
|
||||
}
|
||||
append = true;
|
||||
let json = serde_json::to_string(&entry)?;
|
||||
conn.write_all(json.as_bytes()).await?;
|
||||
}
|
||||
conn.write_all("]".as_bytes()).await?;
|
||||
Ok(Some(200))
|
||||
}
|
||||
50
rust/src/webserver/get_static.rs
Normal file
50
rust/src/webserver/get_static.rs
Normal file
@@ -0,0 +1,50 @@
|
||||
use crate::fat_error::FatError;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_nal::io::{Read, Write};
|
||||
|
||||
pub(crate) async fn serve_favicon<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
) -> Result<Option<u32>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
conn.initiate_response(200, Some("OK"), &[("Content-Type", "image/x-icon")])
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("favicon.ico")).await?;
|
||||
Ok(Some(200))
|
||||
}
|
||||
|
||||
pub(crate) async fn serve_index<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
) -> Result<Option<u32>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[("Content-Type", "text/html"), ("Content-Encoding", "gzip")],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("index.html.gz")).await?;
|
||||
Ok(Some(200))
|
||||
}
|
||||
|
||||
pub(crate) async fn serve_bundle<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
) -> Result<Option<u32>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Content-Type", "text/javascript"),
|
||||
("Content-Encoding", "gzip"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("bundle.js.gz")).await?;
|
||||
Ok(Some(200))
|
||||
}
|
||||
@@ -1,122 +1,42 @@
|
||||
//offer ota and config mode
|
||||
|
||||
use crate::config::PlantControllerConfig;
|
||||
use crate::hal::rtc::X25;
|
||||
use crate::hal::{esp_set_time, esp_time};
|
||||
use crate::log::LOG_ACCESS;
|
||||
use crate::tank::determine_tank_state;
|
||||
mod backup_manager;
|
||||
mod file_manager;
|
||||
mod get_json;
|
||||
mod get_log;
|
||||
mod get_static;
|
||||
mod post_json;
|
||||
|
||||
use crate::fat_error::{FatError, FatResult};
|
||||
use crate::{bail, do_secure_pump, get_version, log::LogMessage, BOARD_ACCESS};
|
||||
use crate::webserver::backup_manager::{backup_config, backup_info, get_backup_config};
|
||||
use crate::webserver::file_manager::{file_operations, list_files};
|
||||
use crate::webserver::get_json::{
|
||||
get_battery_state, get_config, get_live_moisture, get_log_localization_config, get_solar_state,
|
||||
get_time, get_timezones, get_version_web, tank_info,
|
||||
};
|
||||
use crate::webserver::get_log::get_log;
|
||||
use crate::webserver::get_static::{serve_bundle, serve_favicon, serve_index};
|
||||
use crate::webserver::post_json::{
|
||||
board_test, night_lamp_test, pump_test, set_config, wifi_scan, write_time,
|
||||
};
|
||||
use crate::{bail, BOARD_ACCESS};
|
||||
use alloc::borrow::ToOwned;
|
||||
use alloc::format;
|
||||
use alloc::string::{String, ToString};
|
||||
use alloc::sync::Arc;
|
||||
use alloc::vec::Vec;
|
||||
use chrono::DateTime;
|
||||
use core::fmt::{Debug, Display};
|
||||
use core::net::{IpAddr, Ipv4Addr, SocketAddr};
|
||||
use core::result::Result::Ok;
|
||||
use core::str::{from_utf8, FromStr};
|
||||
use core::sync::atomic::{AtomicBool, Ordering};
|
||||
use chrono_tz::Tz;
|
||||
use edge_http::io::server::{Connection, Handler, Server};
|
||||
use edge_http::Method;
|
||||
use edge_nal::TcpBind;
|
||||
use edge_nal::io::{Read, Write};
|
||||
use edge_nal_embassy::{Tcp, TcpBuffers};
|
||||
use embassy_net::Stack;
|
||||
use embassy_time::Instant;
|
||||
use embedded_io_async::{Read, Write};
|
||||
use esp_println::println;
|
||||
use log::info;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
struct SSIDList {
|
||||
ssids: Vec<String>,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
struct LoadData<'a> {
|
||||
rtc: &'a str,
|
||||
native: &'a str,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
struct Moistures {
|
||||
moisture_a: Vec<String>,
|
||||
moisture_b: Vec<String>,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Debug)]
|
||||
struct SolarState {
|
||||
mppt_voltage: f32,
|
||||
mppt_current: f32,
|
||||
is_day: bool,
|
||||
}
|
||||
|
||||
#[derive(Deserialize, Debug)]
|
||||
struct SetTime<'a> {
|
||||
time: &'a str,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Deserialize, Clone, Debug, PartialEq)]
|
||||
pub struct TestPump {
|
||||
pump: usize,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Deserialize, PartialEq, Debug)]
|
||||
pub struct WebBackupHeader {
|
||||
timestamp: String,
|
||||
size: u16,
|
||||
}
|
||||
|
||||
#[derive(Deserialize)]
|
||||
pub struct NightLampCommand {
|
||||
active: bool,
|
||||
}
|
||||
//
|
||||
//
|
||||
|
||||
//
|
||||
|
||||
//
|
||||
// fn get_live_moisture(
|
||||
// _request: &mut Request<&mut EspHttpConnection>,
|
||||
// ) -> Result<Option<std::string::String>, anyhow::Error> {
|
||||
// let mut board = BOARD_ACCESS.lock().expect("Should never fail");
|
||||
// let plant_state =
|
||||
// Vec::from_iter((0..PLANT_COUNT).map(|i| PlantState::read_hardware_state(i, &mut board)));
|
||||
// let a = Vec::from_iter(plant_state.iter().map(|s| match &s.sensor_a {
|
||||
// MoistureSensorState::Disabled => "disabled".to_string(),
|
||||
// MoistureSensorState::MoistureValue {
|
||||
// raw_hz,
|
||||
// moisture_percent,
|
||||
// } => {
|
||||
// format!("{moisture_percent:.2}% {raw_hz}hz",)
|
||||
// }
|
||||
// MoistureSensorState::SensorError(err) => format!("{err:?}"),
|
||||
// }));
|
||||
// let b = Vec::from_iter(plant_state.iter().map(|s| match &s.sensor_b {
|
||||
// MoistureSensorState::Disabled => "disabled".to_string(),
|
||||
// MoistureSensorState::MoistureValue {
|
||||
// raw_hz,
|
||||
// moisture_percent,
|
||||
// } => {
|
||||
// format!("{moisture_percent:.2}% {raw_hz}hz",)
|
||||
// }
|
||||
// MoistureSensorState::SensorError(err) => format!("{err:?}"),
|
||||
// }));
|
||||
//
|
||||
// let data = Moistures {
|
||||
// moisture_a: a,
|
||||
// moisture_b: b,
|
||||
// };
|
||||
// let json = serde_json::to_string(&data)?;
|
||||
//
|
||||
// anyhow::Ok(Some(json))
|
||||
// }
|
||||
//
|
||||
//
|
||||
// fn ota(
|
||||
// request: &mut Request<&mut EspHttpConnection>,
|
||||
// ) -> Result<Option<std::string::String>, anyhow::Error> {
|
||||
@@ -164,11 +84,11 @@ pub struct NightLampCommand {
|
||||
// }
|
||||
//
|
||||
|
||||
struct HttpHandler {
|
||||
struct HTTPRequestRouter {
|
||||
reboot_now: Arc<AtomicBool>,
|
||||
}
|
||||
|
||||
impl Handler for HttpHandler {
|
||||
impl Handler for HTTPRequestRouter {
|
||||
type Error<E: Debug> = FatError;
|
||||
async fn handle<'a, T, const N: usize>(
|
||||
&self,
|
||||
@@ -186,159 +106,15 @@ impl Handler for HttpHandler {
|
||||
|
||||
let prefix = "/file?filename=";
|
||||
let status = if path.starts_with(prefix) {
|
||||
let filename = &path[prefix.len()..];
|
||||
info!("file request for {} with method {}", filename, method);
|
||||
match method {
|
||||
Method::Delete => {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.delete_file(filename.to_owned())
|
||||
.await?;
|
||||
Some(200)
|
||||
}
|
||||
Method::Get => {
|
||||
let disp = format!("attachment; filename=\"{filename}\"");
|
||||
let size = {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.get_size(filename.to_owned())
|
||||
.await?
|
||||
};
|
||||
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Content-Type", "application/octet-stream"),
|
||||
("Content-Disposition", disp.as_str()),
|
||||
("Content-Length", &format!("{}", size)),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
|
||||
let mut chunk = 0;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
let read_chunk = board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.get_file(filename.to_owned(), chunk)
|
||||
.await?;
|
||||
let length = read_chunk.1;
|
||||
if length == 0 {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
}
|
||||
let data = &read_chunk.0[0..length];
|
||||
conn.write_all(data).await?;
|
||||
if length < read_chunk.0.len() {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
}
|
||||
chunk = chunk + 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
Some(200)
|
||||
}
|
||||
Method::Post => {
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
//ensure file is deleted, otherwise we would need to truncate the file which will not work with streaming
|
||||
let _ = board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.delete_file(filename.to_owned())
|
||||
.await;
|
||||
}
|
||||
|
||||
let mut offset = 0_usize;
|
||||
let mut chunk = 0;
|
||||
loop {
|
||||
let mut buf = [0_u8; 1024];
|
||||
let to_write = conn.read(&mut buf).await?;
|
||||
if to_write == 0 {
|
||||
info!("file request for {} finished", filename);
|
||||
break;
|
||||
} else {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
board
|
||||
.board_hal
|
||||
.get_esp()
|
||||
.write_file(filename.to_owned(), offset as u32, &buf[0..to_write])
|
||||
.await?;
|
||||
}
|
||||
offset = offset + to_write;
|
||||
chunk = chunk + 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
Some(200)
|
||||
}
|
||||
_ => None,
|
||||
}
|
||||
file_operations(conn, method, &path, &prefix).await?
|
||||
} else {
|
||||
match method {
|
||||
Method::Get => match path {
|
||||
"/favicon.ico" => {
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[("Content-Type", "image/x-icon")],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("favicon.ico")).await?;
|
||||
Some(200)
|
||||
}
|
||||
"/" => {
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[("Content-Type", "text/html"), ("Content-Encoding", "gzip")],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("index.html.gz")).await?;
|
||||
Some(200)
|
||||
}
|
||||
"/bundle.js" => {
|
||||
conn.initiate_response(
|
||||
200,
|
||||
Some("OK"),
|
||||
&[
|
||||
("Content-Type", "text/javascript"),
|
||||
("Content-Encoding", "gzip"),
|
||||
],
|
||||
)
|
||||
.await?;
|
||||
conn.write_all(include_bytes!("bundle.js.gz")).await?;
|
||||
Some(200)
|
||||
}
|
||||
"/log" => {
|
||||
get_log(conn).await?;
|
||||
Some(200)
|
||||
}
|
||||
"/get_backup_config" => {
|
||||
get_backup_config(conn).await?;
|
||||
Some(200)
|
||||
}
|
||||
"/favicon.ico" => serve_favicon(conn).await?,
|
||||
"/" => serve_index(conn).await?,
|
||||
"/bundle.js" => serve_bundle(conn).await?,
|
||||
"/log" => get_log(conn).await?,
|
||||
"/get_backup_config" => get_backup_config(conn).await?,
|
||||
&_ => {
|
||||
let json = match path {
|
||||
"/version" => Some(get_version_web(conn).await),
|
||||
@@ -350,7 +126,8 @@ impl Handler for HttpHandler {
|
||||
"/log_localization" => Some(get_log_localization_config(conn).await),
|
||||
"/tank" => Some(tank_info(conn).await),
|
||||
"/backup_info" => Some(backup_info(conn).await),
|
||||
"/timezones" => Some(get_timezones(conn).await),
|
||||
"/timezones" => Some(get_timezones().await),
|
||||
"/moisture" => Some(get_live_moisture(conn).await),
|
||||
_ => None,
|
||||
};
|
||||
match json {
|
||||
@@ -367,13 +144,19 @@ impl Handler for HttpHandler {
|
||||
"/backup_config" => Some(backup_config(conn).await),
|
||||
"/pumptest" => Some(pump_test(conn).await),
|
||||
"/lamptest" => Some(night_lamp_test(conn).await),
|
||||
"/boardtest" => Some(board_test(conn).await),
|
||||
"/boardtest" => Some(board_test().await),
|
||||
"/reboot" => {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.get_esp().set_restart_to_conf(true);
|
||||
self.reboot_now.store(true, Ordering::Relaxed);
|
||||
Some(Ok(None))
|
||||
}
|
||||
"/exit" => {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.get_esp().set_restart_to_conf(false);
|
||||
self.reboot_now.store(true, Ordering::Relaxed);
|
||||
Some(Ok(None))
|
||||
}
|
||||
_ => None,
|
||||
};
|
||||
match json {
|
||||
@@ -401,265 +184,6 @@ impl Handler for HttpHandler {
|
||||
}
|
||||
}
|
||||
|
||||
async fn get_timezones<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
// Get all timezones using chrono-tz
|
||||
let timezones: Vec<&'static str> = chrono_tz::TZ_VARIANTS.iter().map(|tz| tz.name()).collect();
|
||||
let json = serde_json::to_string(&timezones)?;
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
async fn board_test<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.test().await?;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
async fn pump_test<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let pump_test: TestPump = serde_json::from_slice(&actual_data)?;
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
|
||||
let config = &board.board_hal.get_config().plants[pump_test.pump].clone();
|
||||
let pump_result = do_secure_pump(&mut board, pump_test.pump, config, false).await;
|
||||
//ensure it is disabled before unwrapping
|
||||
board.board_hal.pump(pump_test.pump, false).await?;
|
||||
|
||||
Ok(Some(serde_json::to_string(&pump_result?)?))
|
||||
}
|
||||
|
||||
async fn night_lamp_test<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let light_command: NightLampCommand = serde_json::from_slice(&actual_data)?;
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.light(light_command.active).await?;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
async fn get_backup_config<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, { N }>,
|
||||
) -> Result<(), FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
// First pass: verify checksum without sending data
|
||||
let mut checksum = X25.digest();
|
||||
let mut chunk = 0_usize;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
let (buf, len, expected_crc) = board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.get_backup_config(chunk)
|
||||
.await?;
|
||||
|
||||
// Update checksum with the actual data bytes of this chunk
|
||||
checksum.update(&buf[..len]);
|
||||
|
||||
let is_last = len == 0 || len < buf.len();
|
||||
if is_last {
|
||||
let actual_crc = checksum.finalize();
|
||||
if actual_crc != expected_crc {
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
conn.initiate_response(
|
||||
409,
|
||||
Some(
|
||||
format!(
|
||||
"Checksum mismatch expected {} got {}",
|
||||
expected_crc, actual_crc
|
||||
)
|
||||
.as_str(),
|
||||
),
|
||||
&[],
|
||||
)
|
||||
.await?;
|
||||
return Ok(());
|
||||
}
|
||||
break;
|
||||
}
|
||||
chunk += 1;
|
||||
}
|
||||
|
||||
// Second pass: stream data
|
||||
conn.initiate_response(200, Some("OK"), &[]).await?;
|
||||
|
||||
let mut chunk = 0_usize;
|
||||
loop {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(chunk as u32).await;
|
||||
let (buf, len, _expected_crc) = board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.get_backup_config(chunk)
|
||||
.await?;
|
||||
|
||||
if len == 0 {
|
||||
break;
|
||||
}
|
||||
|
||||
conn.write_all(&buf[..len]).await?;
|
||||
|
||||
if len < buf.len() {
|
||||
break;
|
||||
}
|
||||
chunk += 1;
|
||||
}
|
||||
BOARD_ACCESS
|
||||
.get()
|
||||
.await
|
||||
.lock()
|
||||
.await
|
||||
.board_hal
|
||||
.clear_progress()
|
||||
.await;
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn backup_config<T, const N: usize>(
|
||||
conn: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut offset = 0_usize;
|
||||
let mut buf = [0_u8; 32];
|
||||
|
||||
let mut checksum = crate::hal::rtc::X25.digest();
|
||||
|
||||
let mut counter = 0;
|
||||
loop {
|
||||
let to_write = conn.read(&mut buf).await?;
|
||||
if to_write == 0 {
|
||||
info!("backup finished");
|
||||
break;
|
||||
} else {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.progress(counter).await;
|
||||
|
||||
counter = counter + 1;
|
||||
board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.backup_config(offset, &buf[0..to_write])
|
||||
.await?;
|
||||
checksum.update(&buf[0..to_write]);
|
||||
}
|
||||
offset = offset + to_write;
|
||||
}
|
||||
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board
|
||||
.board_hal
|
||||
.get_rtc_module()
|
||||
.backup_config_finalize(checksum.finalize(), offset)
|
||||
.await?;
|
||||
board.board_hal.clear_progress().await;
|
||||
Ok(Some("saved".to_owned()))
|
||||
}
|
||||
|
||||
async fn backup_info<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> Result<Option<String>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let header = board.board_hal.get_rtc_module().get_backup_info().await;
|
||||
let json = match header {
|
||||
Ok(h) => {
|
||||
let timestamp = DateTime::from_timestamp_millis(h.timestamp).unwrap();
|
||||
let wbh = WebBackupHeader {
|
||||
timestamp: timestamp.to_rfc3339(),
|
||||
size: h.size,
|
||||
};
|
||||
serde_json::to_string(&wbh)?
|
||||
}
|
||||
Err(err) => {
|
||||
let wbh = WebBackupHeader {
|
||||
timestamp: err.to_string(),
|
||||
size: 0,
|
||||
};
|
||||
serde_json::to_string(&wbh)?
|
||||
}
|
||||
};
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
async fn tank_info<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> Result<Option<String>, FatError>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let tank_state = determine_tank_state(&mut board).await;
|
||||
//should be multisampled
|
||||
let sensor = board.board_hal.get_tank_sensor()?;
|
||||
|
||||
let water_temp: FatResult<f32> = sensor.water_temperature_c().await;
|
||||
Ok(Some(serde_json::to_string(&tank_state.as_mqtt_info(
|
||||
&board.board_hal.get_config().tank,
|
||||
&water_temp,
|
||||
))?))
|
||||
}
|
||||
|
||||
async fn write_time<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let time: SetTime = serde_json::from_slice(&actual_data)?;
|
||||
let parsed = DateTime::parse_from_rfc3339(time.time).unwrap();
|
||||
esp_set_time(parsed).await;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
async fn set_config<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let all = read_up_to_bytes_from_request(request, Some(4096)).await?;
|
||||
let length = all.len();
|
||||
let config: PlantControllerConfig = serde_json::from_slice(&all)?;
|
||||
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.get_esp().save_config(all).await?;
|
||||
log::info!("Wrote config config {:?} with size {}", config, length);
|
||||
board.board_hal.set_config(config);
|
||||
Ok(Some("saved".to_string()))
|
||||
}
|
||||
|
||||
async fn read_up_to_bytes_from_request<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
limit: Option<usize>,
|
||||
@@ -683,181 +207,27 @@ where
|
||||
}
|
||||
data_store.push(actual_data.to_owned());
|
||||
}
|
||||
let allvec = data_store.concat();
|
||||
log::info!("Raw data {}", from_utf8(&allvec)?);
|
||||
Ok(allvec)
|
||||
}
|
||||
|
||||
async fn wifi_scan<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
info!("start wifi scan");
|
||||
let mut ssids: Vec<String> = Vec::new();
|
||||
let scan_result = board.board_hal.get_esp().wifi_scan().await?;
|
||||
scan_result
|
||||
.iter()
|
||||
.for_each(|s| ssids.push(s.ssid.to_string()));
|
||||
let ssid_json = serde_json::to_string(&SSIDList { ssids })?;
|
||||
info!("Sending ssid list {}", &ssid_json);
|
||||
Ok(Some(ssid_json))
|
||||
}
|
||||
|
||||
async fn get_log<T, const N: usize>(conn: &mut Connection<'_, T, N>) -> FatResult<()>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let log = LOG_ACCESS.lock().await.get();
|
||||
conn.initiate_response(200, Some("OK"), &[("Content-Type", "text/javascript")])
|
||||
.await?;
|
||||
conn.write_all("[".as_bytes()).await?;
|
||||
let mut append = false;
|
||||
for entry in log {
|
||||
if append {
|
||||
conn.write_all(",".as_bytes()).await?;
|
||||
}
|
||||
append = true;
|
||||
let json = serde_json::to_string(&entry)?;
|
||||
conn.write_all(json.as_bytes()).await?;
|
||||
}
|
||||
conn.write_all("]".as_bytes()).await?;
|
||||
Ok(())
|
||||
}
|
||||
|
||||
async fn get_log_localization_config<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
Ok(Some(serde_json::to_string(
|
||||
&LogMessage::to_log_localisation_config(),
|
||||
)?))
|
||||
}
|
||||
async fn list_files<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let result = board.board_hal.get_esp().list_files().await?;
|
||||
let file_list_json = serde_json::to_string(&result)?;
|
||||
Ok(Some(file_list_json))
|
||||
}
|
||||
async fn get_config<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let json = serde_json::to_string(&board.board_hal.get_config())?;
|
||||
Ok(Some(json))
|
||||
}
|
||||
|
||||
async fn get_solar_state<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let state = SolarState {
|
||||
mppt_voltage: board.board_hal.get_mptt_voltage().await?.as_millivolts() as f32,
|
||||
mppt_current: board.board_hal.get_mptt_current().await?.as_milliamperes() as f32,
|
||||
is_day: board.board_hal.is_day(),
|
||||
};
|
||||
Ok(Some(serde_json::to_string(&state)?))
|
||||
}
|
||||
|
||||
async fn get_battery_state<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let battery_state = board
|
||||
.board_hal
|
||||
.get_battery_monitor()
|
||||
.get_battery_state()
|
||||
.await?;
|
||||
Ok(Some(serde_json::to_string(&battery_state)?))
|
||||
}
|
||||
|
||||
async fn get_version_web<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
Ok(Some(serde_json::to_string(&get_version(&mut board).await)?))
|
||||
}
|
||||
|
||||
async fn get_time<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
let conf = board.board_hal.get_config();
|
||||
let tz = Tz::from_str(conf.timezone.as_ref().unwrap().as_str()).unwrap();
|
||||
let native = esp_time().await.with_timezone(&tz).to_rfc3339();
|
||||
|
||||
let rtc = match board.board_hal.get_rtc_module().get_rtc_time().await {
|
||||
Ok(time) => time.with_timezone(&tz).to_rfc3339(),
|
||||
Err(err) => {
|
||||
format!("Error getting time: {}", err)
|
||||
}
|
||||
};
|
||||
|
||||
let data = LoadData {
|
||||
rtc: rtc.as_str(),
|
||||
native: native.as_str(),
|
||||
};
|
||||
let json = serde_json::to_string(&data)?;
|
||||
|
||||
Ok(Some(json))
|
||||
let final_buffer = data_store.concat();
|
||||
Ok(final_buffer)
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
pub async fn httpd(reboot_now: Arc<AtomicBool>, stack: Stack<'static>) {
|
||||
pub async fn http_server(reboot_now: Arc<AtomicBool>, stack: Stack<'static>) {
|
||||
let buffer: TcpBuffers<2, 1024, 1024> = TcpBuffers::new();
|
||||
let tcp = Tcp::new(stack, &buffer);
|
||||
let acceptor = tcp
|
||||
.bind(SocketAddr::new(IpAddr::V4(Ipv4Addr::new(0, 0, 0, 0)), 80))
|
||||
.bind(SocketAddr::new(IpAddr::V4(Ipv4Addr::UNSPECIFIED), 80))
|
||||
.await
|
||||
.unwrap();
|
||||
|
||||
let mut server: Server<2, 512, 15> = Server::new();
|
||||
server
|
||||
.run(Some(5000), acceptor, HttpHandler { reboot_now })
|
||||
.run(Some(5000), acceptor, HTTPRequestRouter { reboot_now })
|
||||
.await
|
||||
.expect("TODO: panic message");
|
||||
println!("Wait for connection...");
|
||||
.expect("Tcp stack error");
|
||||
info!("Webserver started and waiting for connections");
|
||||
|
||||
// server
|
||||
// .fn_handler("/moisture", Method::Get, |request| {
|
||||
// handle_error_to500(request, get_live_moisture)
|
||||
// })
|
||||
// .unwrap();
|
||||
|
||||
// server
|
||||
// .fn_handler("/ota", Method::Post, |request| {
|
||||
// handle_error_to500(request, ota)
|
||||
// })
|
||||
// .unwrap();
|
||||
// server
|
||||
// .fn_handler("/ota", Method::Options, |request| {
|
||||
// cors_response(request, 200, "")
|
||||
// })
|
||||
// .unwrap();
|
||||
// let reboot_now_for_reboot = reboot_now.clone();
|
||||
// server
|
||||
// .fn_handler("/reboot", Method::Post, move |_| {
|
||||
// BOARD_ACCESS
|
||||
// .lock()
|
||||
// .unwrap()
|
||||
// .board_hal
|
||||
// .get_esp()
|
||||
// .set_restart_to_conf(true);
|
||||
// reboot_now_for_reboot.store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// anyhow::Ok(())
|
||||
// })
|
||||
// .unwrap();
|
||||
//
|
||||
// unsafe { vTaskDelay(1) };
|
||||
//
|
||||
// let reboot_now_for_exit = reboot_now.clone();
|
||||
// server
|
||||
// .fn_handler("/exit", Method::Post, move |_| {
|
||||
// reboot_now_for_exit.store(true, std::sync::atomic::Ordering::Relaxed);
|
||||
// anyhow::Ok(())
|
||||
// })
|
||||
// .unwrap();
|
||||
// server
|
||||
//TODO https if mbed_esp lands
|
||||
}
|
||||
|
||||
async fn handle_json<'a, T, const N: usize>(
|
||||
@@ -866,7 +236,7 @@ async fn handle_json<'a, T, const N: usize>(
|
||||
) -> FatResult<u32>
|
||||
where
|
||||
T: Read + Write,
|
||||
<T as embedded_io_async::ErrorType>::Error: Debug,
|
||||
<T as edge_nal::io::ErrorType>::Error: Debug,
|
||||
{
|
||||
match chain {
|
||||
Ok(answer) => match answer {
|
||||
|
||||
114
rust/src/webserver/post_json.rs
Normal file
114
rust/src/webserver/post_json.rs
Normal file
@@ -0,0 +1,114 @@
|
||||
use crate::config::PlantControllerConfig;
|
||||
use crate::fat_error::FatResult;
|
||||
use crate::webserver::read_up_to_bytes_from_request;
|
||||
use crate::{do_secure_pump, BOARD_ACCESS};
|
||||
use alloc::borrow::ToOwned;
|
||||
use alloc::string::{String, ToString};
|
||||
use alloc::vec::Vec;
|
||||
use chrono::DateTime;
|
||||
use edge_http::io::server::Connection;
|
||||
use edge_nal::io::{Read, Write};
|
||||
use esp_radio::wifi::ap::AccessPointInfo;
|
||||
use log::info;
|
||||
use serde::{Deserialize, Serialize};
|
||||
|
||||
#[derive(Deserialize)]
|
||||
pub struct NightLampCommand {
|
||||
active: bool,
|
||||
}
|
||||
#[derive(Serialize, Debug)]
|
||||
struct SSIDList {
|
||||
ssids: Vec<String>,
|
||||
}
|
||||
#[derive(Deserialize, Debug)]
|
||||
struct SetTime<'a> {
|
||||
time: &'a str,
|
||||
}
|
||||
|
||||
#[derive(Serialize, Deserialize, Clone, Debug, PartialEq)]
|
||||
pub struct TestPump {
|
||||
pump: usize,
|
||||
}
|
||||
|
||||
pub(crate) async fn wifi_scan<T, const N: usize>(
|
||||
_request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
info!("start wifi scan");
|
||||
let mut ssids: Vec<String> = Vec::new();
|
||||
let scan_result: Vec<AccessPointInfo> = board.board_hal.get_esp().wifi_scan().await?;
|
||||
scan_result
|
||||
.iter()
|
||||
.for_each(|s| ssids.push(s.ssid.as_str().to_owned()));
|
||||
let ssid_json = serde_json::to_string(&SSIDList { ssids })?;
|
||||
info!("Sending ssid list {}", &ssid_json);
|
||||
Ok(Some(ssid_json))
|
||||
}
|
||||
|
||||
pub(crate) async fn board_test() -> FatResult<Option<String>> {
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.test().await?;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
pub(crate) async fn pump_test<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let pump_test: TestPump = serde_json::from_slice(&actual_data)?;
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
|
||||
let config = &board.board_hal.get_config().plants[pump_test.pump].clone();
|
||||
let pump_result = do_secure_pump(&mut board, pump_test.pump, config, false).await;
|
||||
//ensure it is disabled before unwrapping
|
||||
board.board_hal.pump(pump_test.pump, false).await?;
|
||||
|
||||
Ok(Some(serde_json::to_string(&pump_result?)?))
|
||||
}
|
||||
|
||||
pub(crate) async fn night_lamp_test<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let light_command: NightLampCommand = serde_json::from_slice(&actual_data)?;
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.light(light_command.active).await?;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
pub(crate) async fn write_time<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let actual_data = read_up_to_bytes_from_request(request, None).await?;
|
||||
let time: SetTime = serde_json::from_slice(&actual_data)?;
|
||||
let parsed = DateTime::parse_from_rfc3339(time.time)?;
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.set_time(&parsed).await?;
|
||||
Ok(None)
|
||||
}
|
||||
|
||||
pub(crate) async fn set_config<T, const N: usize>(
|
||||
request: &mut Connection<'_, T, N>,
|
||||
) -> FatResult<Option<String>>
|
||||
where
|
||||
T: Read + Write,
|
||||
{
|
||||
let all = read_up_to_bytes_from_request(request, Some(4096)).await?;
|
||||
let length = all.len();
|
||||
let config: PlantControllerConfig = serde_json::from_slice(&all)?;
|
||||
|
||||
let mut board = BOARD_ACCESS.get().await.lock().await;
|
||||
board.board_hal.get_esp().save_config(all).await?;
|
||||
info!("Wrote config config {:?} with size {}", config, length);
|
||||
board.board_hal.set_config(config);
|
||||
Ok(Some("saved".to_string()))
|
||||
}
|
||||
Reference in New Issue
Block a user