Compare commits

...

4 Commits

21 changed files with 600 additions and 470 deletions

View File

@ -1,26 +1,28 @@
[build] [build]
#target = "xtensa-esp32-espidf" rustflags = [
target = "riscv32imac-esp-espidf" # Required to obtain backtraces (e.g. when using the "esp-backtrace" crate.)
# NOTE: May negatively impact performance of produced code
"-C", "force-frame-pointers",
"-Z", "stack-protector=all",
]
[target.riscv32imac-esp-espidf] target = "riscv32imac-unknown-none-elf"
linker = "ldproxy"
[target.riscv32imac-unknown-none-elf]
runner = "espflash flash --monitor --chip esp32c6"
#runner = "espflash flash --monitor --baud 921600 --partition-table partitions.csv -b no-reset" # Select this runner in case of usb ttl #runner = "espflash flash --monitor --baud 921600 --partition-table partitions.csv -b no-reset" # Select this runner in case of usb ttl
runner = "espflash flash --monitor" #runner = "espflash flash --monitor"
#runner = "cargo runner" #runner = "cargo runner"
#runner = "espflash flash --monitor --partition-table partitions.csv -b no-reset" # create upgrade image file for webupload #runner = "espflash flash --monitor --partition-table partitions.csv -b no-reset" # create upgrade image file for webupload
# runner = espflash erase-parts otadata //ensure flash is clean # runner = espflash erase-parts otadata //ensure flash is clean
rustflags = ["--cfg", "espidf_time64"] # Extending time_t for ESP IDF 5: https://github.com/esp-rs/rust/issues/110
[unstable]
build-std = ["std", "panic_abort"]
[env] [env]
MCU = "esp32c6"
# Note: this variable is not used by the pio builder (`cargo build --features pio`)
ESP_IDF_VERSION = "v5.2.1"
CHRONO_TZ_TIMEZONE_FILTER = "UTC|America/New_York|America/Chicago|America/Los_Angeles|Europe/London|Europe/Berlin|Europe/Paris|Asia/Tokyo|Asia/Shanghai|Asia/Kolkata|Australia/Sydney|America/Sao_Paulo|Africa/Johannesburg|Asia/Dubai|Pacific/Auckland" CHRONO_TZ_TIMEZONE_FILTER = "UTC|America/New_York|America/Chicago|America/Los_Angeles|Europe/London|Europe/Berlin|Europe/Paris|Asia/Tokyo|Asia/Shanghai|Asia/Kolkata|Australia/Sydney|America/Sao_Paulo|Africa/Johannesburg|Asia/Dubai|Pacific/Auckland"
CARGO_WORKSPACE_DIR = { value = "", relative = true } CARGO_WORKSPACE_DIR = { value = "", relative = true }
RUST_BACKTRACE = "full" ESP_LOG="info"
[unstable]
build-std = ["alloc", "core"]

View File

@ -44,59 +44,104 @@ command = [
[package.metadata.espflash] [package.metadata.espflash]
partition_table = "partitions.csv" partition_table = "partitions.csv"
[features]
default = ["std", "esp-idf-svc/native"]
pio = ["esp-idf-svc/pio"]
std = ["alloc", "esp-idf-svc/binstart", "esp-idf-svc/std"]
alloc = ["esp-idf-svc/alloc"]
nightly = ["esp-idf-svc/nightly"]
experimental = ["esp-idf-svc/experimental"]
#embassy = ["esp-idf-svc/embassy-sync", "esp-idf-svc/critical-section", "esp-idf-svc/embassy-time-driver"]
[dependencies] [dependencies]
#ESP stuff #ESP stuff
embedded-svc = { version = "0.28.1", features = ["experimental"] } esp-bootloader-esp-idf = { version = "0.2.0", features = ["esp32c6"] }
esp-idf-hal = "0.45.2" esp-hal = { version = "=1.0.0-rc.0", features = [
esp-idf-sys = { version = "0.36.1", features = ["binstart", "native"] } "esp32c6",
esp-idf-svc = { version = "0.51.0", default-features = false } "log-04",
"unstable",
] }
log = "0.4.27"
embassy-net = { version = "0.7.0", 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",
] }
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-20480",
] }
embassy-time = { version = "0.4.0", features = ["log"] }
esp-hal-embassy = { version = "0.9.0", features = ["esp32c6", "log-04"] }
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 = [
"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"
embedded-hal = "1.0.0" embedded-hal = "1.0.0"
heapless = { version = "0.8", features = ["serde"] } heapless = { version = "0.8", features = ["serde"] }
embedded-hal-bus = { version = "0.3.0", features = ["std"] } embedded-hal-bus = { version = "0.3.0" }
#Hardware additional driver #Hardware additional driver
ds18b20 = "0.1.1" #ds18b20 = "0.1.1"
bq34z100 = { version = "0.3.0", features = ["flashstream"] } #bq34z100 = { version = "0.3.0", default-features = false }
one-wire-bus = "0.1.1" one-wire-bus = "0.1.1"
ds323x = "0.6.0" ds323x = "0.6.0"
#pure code dependencies #pure code dependencies
once_cell = "1.19.0" #once_cell = "1.19.0"
anyhow = { version = "1.0.75", features = ["std", "backtrace"] } anyhow = { version = "1.0.75", default-features = false }
strum = { version = "0.27.0", features = ["derive"] } #strum = { version = "0.27.0", default-feature = false, features = ["derive"] }
measurements = "0.11.0" measurements = "0.11.0"
#json #json
serde = { version = "1.0.192", features = ["derive"] } serde = { version = "1.0.219", features = ["derive", "alloc"], default-features = false }
serde_json = "1.0.108" serde_json = { version = "1.0.143", default-features = false, features = ["alloc"] }
#timezone #timezone
chrono = { version = "0.4.23", default-features = false, features = ["iana-time-zone", "alloc", "serde"] } chrono = { version = "0.4.23", default-features = false, features = ["iana-time-zone", "alloc", "serde"] }
chrono-tz = { version = "0.10.3", default-features = false, features = ["filter-by-regex"] } chrono-tz = { version = "0.10.3", default-features = false, features = ["filter-by-regex"] }
eeprom24x = "0.7.2" eeprom24x = "0.7.2"
url = "2.5.3" #url = "2.5.3"
crc = "3.2.1" crc = "3.2.1"
bincode = "2.0.1" bincode = { version = "2.0.1", default-features = false, features = ["alloc", "serde"] }
ringbuffer = "0.15.0" ringbuffer = "0.15.0"
text-template = "0.1.0" #text-template = "0.1.0"
strum_macros = "0.27.0" strum_macros = "0.27.0"
esp-ota = { version = "0.2.2", features = ["log"] } #esp-ota = { version = "0.2.2", features = ["log"] }
unit-enum = "1.4.1" unit-enum = "1.4.1"
pca9535 = { version = "2.0.0", features = ["std"] } pca9535 = { version = "2.0.0" }
ina219 = { version = "0.2.0", features = ["std"] } ina219 = { version = "0.2.0" }
embedded-storage = "=0.3.1" embedded-storage = "=0.3.1"
ekv = "1.0.0" ekv = "1.0.0"
embedded-can = "0.4.1" embedded-can = "0.4.1"
critical-section = "1.2.0"
portable-atomic = "1.11.1"
embassy-sync = { version = "0.7.2", features = ["log"] }
async-trait = "0.1.89"
[patch.crates-io] [patch.crates-io]
@ -108,6 +153,4 @@ embedded-can = "0.4.1"
#bq34z100 = { path = "../../bq34z100_rust" } #bq34z100 = { path = "../../bq34z100_rust" }
[build-dependencies] [build-dependencies]
cc = "=1.1.30"
embuild = { version = "0.32.0", features = ["espidf"] }
vergen = { version = "8.2.6", features = ["build", "git", "gitcl"] } vergen = { version = "8.2.6", features = ["build", "git", "gitcl"] }

View File

@ -1,6 +1,54 @@
use std::process::Command; use std::process::Command;
use vergen::EmitBuilder; use vergen::EmitBuilder;
fn linker_be_nice() {
let args: Vec<String> = std::env::args().collect();
if args.len() > 1 {
let kind = &args[1];
let what = &args[2];
match kind.as_str() {
"undefined-symbol" => match what.as_str() {
"_defmt_timestamp" => {
eprintln!();
eprintln!("💡 `defmt` not found - make sure `defmt.x` is added as a linker script and you have included `use defmt_rtt as _;`");
eprintln!();
}
"_stack_start" => {
eprintln!();
eprintln!("💡 Is the linker script `linkall.x` missing?");
eprintln!();
}
"esp_wifi_preempt_enable"
| "esp_wifi_preempt_yield_task"
| "esp_wifi_preempt_task_create" => {
eprintln!();
eprintln!("💡 `esp-wifi` has no scheduler enabled. Make sure you have the `builtin-scheduler` feature enabled, or that you provide an external scheduler.");
eprintln!();
}
"embedded_test_linker_file_not_added_to_rustflags" => {
eprintln!();
eprintln!("💡 `embedded-test` not found - make sure `embedded-test.x` is added as a linker script for tests");
eprintln!();
}
_ => (),
},
// we don't have anything helpful for "missing-lib" yet
_ => {
std::process::exit(1);
}
}
std::process::exit(0);
}
println!(
"cargo:rustc-link-arg=--error-handling-script={}",
std::env::current_exe().unwrap().display()
);
}
fn main() { fn main() {
println!("cargo:rerun-if-changed=./src/src_webpack"); println!("cargo:rerun-if-changed=./src/src_webpack");
Command::new("rm") Command::new("rm")
@ -64,7 +112,6 @@ fn main() {
.unwrap(); .unwrap();
} }
} }
linker_be_nice();
embuild::espidf::sysenv::output();
let _ = EmitBuilder::builder().all_git().all_build().emit(); let _ = EmitBuilder::builder().all_git().all_build().emit();
} }

View File

@ -1,22 +1,20 @@
use anyhow::anyhow; use anyhow::anyhow;
use bq34z100::{Bq34Z100Error, Bq34z100g1, Bq34z100g1Driver}; use async_trait::async_trait;
use embedded_hal_bus::i2c::MutexDevice;
use esp_idf_hal::delay::Delay;
use esp_idf_hal::i2c::{I2cDriver, I2cError};
use measurements::Temperature; use measurements::Temperature;
use serde::Serialize; use serde::Serialize;
#[async_trait]
pub trait BatteryInteraction { pub trait BatteryInteraction {
fn state_charge_percent(&mut self) -> Result<f32, BatteryError>; async fn state_charge_percent(&mut self) -> Result<f32, BatteryError>;
fn remaining_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>; async fn remaining_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>;
fn max_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>; async fn max_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>;
fn design_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>; async fn design_milli_ampere_hour(&mut self) -> Result<u16, BatteryError>;
fn voltage_milli_volt(&mut self) -> Result<u16, BatteryError>; async fn voltage_milli_volt(&mut self) -> Result<u16, BatteryError>;
fn average_current_milli_ampere(&mut self) -> Result<i16, BatteryError>; async fn average_current_milli_ampere(&mut self) -> Result<i16, BatteryError>;
fn cycle_count(&mut self) -> Result<u16, BatteryError>; async fn cycle_count(&mut self) -> Result<u16, BatteryError>;
fn state_health_percent(&mut self) -> Result<u16, BatteryError>; async fn state_health_percent(&mut self) -> Result<u16, BatteryError>;
fn bat_temperature(&mut self) -> Result<u16, BatteryError>; async fn bat_temperature(&mut self) -> Result<u16, BatteryError>;
fn get_battery_state(&mut self) -> Result<BatteryState, BatteryError>; async fn get_battery_state(&mut self) -> Result<BatteryState, BatteryError>;
} }
#[derive(Debug, Serialize)] #[derive(Debug, Serialize)]
@ -158,56 +156,56 @@ impl BatteryInteraction for BQ34Z100G1<'_> {
pub fn print_battery_bq34z100( pub fn print_battery_bq34z100(
battery_driver: &mut Bq34z100g1Driver<MutexDevice<I2cDriver<'_>>, Delay>, battery_driver: &mut Bq34z100g1Driver<MutexDevice<I2cDriver<'_>>, Delay>,
) -> anyhow::Result<(), Bq34Z100Error<I2cError>> { ) -> anyhow::Result<(), Bq34Z100Error<I2cError>> {
println!("Try communicating with battery"); log::info!("Try communicating with battery");
let fwversion = battery_driver.fw_version().unwrap_or_else(|e| { let fwversion = battery_driver.fw_version().unwrap_or_else(|e| {
println!("Firmware {:?}", e); log::info!("Firmware {:?}", e);
0 0
}); });
println!("fw version is {}", fwversion); log::info!("fw version is {}", fwversion);
let design_capacity = battery_driver.design_capacity().unwrap_or_else(|e| { let design_capacity = battery_driver.design_capacity().unwrap_or_else(|e| {
println!("Design capacity {:?}", e); log::info!("Design capacity {:?}", e);
0 0
}); });
println!("Design Capacity {}", design_capacity); log::info!("Design Capacity {}", design_capacity);
if design_capacity == 1000 { if design_capacity == 1000 {
println!("Still stock configuring battery, readouts are likely to be wrong!"); log::info!("Still stock configuring battery, readouts are likely to be wrong!");
} }
let flags = battery_driver.get_flags_decoded()?; let flags = battery_driver.get_flags_decoded()?;
println!("Flags {:?}", flags); log::info!("Flags {:?}", flags);
let chem_id = battery_driver.chem_id().unwrap_or_else(|e| { let chem_id = battery_driver.chem_id().unwrap_or_else(|e| {
println!("Chemid {:?}", e); log::info!("Chemid {:?}", e);
0 0
}); });
let bat_temp = battery_driver.internal_temperature().unwrap_or_else(|e| { let bat_temp = battery_driver.internal_temperature().unwrap_or_else(|e| {
println!("Bat Temp {:?}", e); log::info!("Bat Temp {:?}", e);
0 0
}); });
let temp_c = Temperature::from_kelvin(bat_temp as f64 / 10_f64).as_celsius(); let temp_c = Temperature::from_kelvin(bat_temp as f64 / 10_f64).as_celsius();
let voltage = battery_driver.voltage().unwrap_or_else(|e| { let voltage = battery_driver.voltage().unwrap_or_else(|e| {
println!("Bat volt {:?}", e); log::info!("Bat volt {:?}", e);
0 0
}); });
let current = battery_driver.current().unwrap_or_else(|e| { let current = battery_driver.current().unwrap_or_else(|e| {
println!("Bat current {:?}", e); log::info!("Bat current {:?}", e);
0 0
}); });
let state = battery_driver.state_of_charge().unwrap_or_else(|e| { let state = battery_driver.state_of_charge().unwrap_or_else(|e| {
println!("Bat Soc {:?}", e); log::info!("Bat Soc {:?}", e);
0 0
}); });
let charge_voltage = battery_driver.charge_voltage().unwrap_or_else(|e| { let charge_voltage = battery_driver.charge_voltage().unwrap_or_else(|e| {
println!("Bat Charge Volt {:?}", e); log::info!("Bat Charge Volt {:?}", e);
0 0
}); });
let charge_current = battery_driver.charge_current().unwrap_or_else(|e| { let charge_current = battery_driver.charge_current().unwrap_or_else(|e| {
println!("Bat Charge Current {:?}", e); log::info!("Bat Charge Current {:?}", e);
0 0
}); });
println!("ChemId: {} Current voltage {} and current {} with charge {}% and temp {} CVolt: {} CCur {}", chem_id, voltage, current, state, temp_c, charge_voltage, charge_current); log::info!("ChemId: {} Current voltage {} and current {} with charge {}% and temp {} CVolt: {} CCur {}", chem_id, voltage, current, state, temp_c, charge_voltage, charge_current);
let _ = battery_driver.unsealed(); let _ = battery_driver.unsealed();
let _ = battery_driver.it_enable(); let _ = battery_driver.it_enable();
anyhow::Result::Ok(()) anyhow::Result::Ok(())

View File

@ -4,30 +4,12 @@ use crate::log::{log, LogMessage};
use crate::STAY_ALIVE; use crate::STAY_ALIVE;
use anyhow::{anyhow, bail, Context}; use anyhow::{anyhow, bail, Context};
use chrono::{DateTime, Utc}; use chrono::{DateTime, Utc};
use embedded_svc::ipv4::IpInfo;
use embedded_svc::mqtt::client::QoS::{AtLeastOnce, ExactlyOnce};
use embedded_svc::wifi::{
AccessPointConfiguration, AccessPointInfo, AuthMethod, ClientConfiguration, Configuration,
};
use esp_idf_hal::delay::Delay;
use esp_idf_hal::gpio::{Level, PinDriver};
use esp_idf_svc::mqtt::client::{EspMqttClient, LwtConfiguration, MqttClientConfiguration};
use esp_idf_svc::sntp;
use esp_idf_svc::sntp::SyncStatus;
use esp_idf_svc::systime::EspSystemTime;
use esp_idf_svc::wifi::config::{ScanConfig, ScanType};
use esp_idf_svc::wifi::EspWifi;
use esp_idf_sys::{esp_spiffs_info, vTaskDelay};
use serde::Serialize; use serde::Serialize;
use std::ffi::CString;
use std::fs; use alloc::{
use std::fs::File; string::{String, ToString},
use std::path::Path; vec::Vec,
use std::result::Result::Ok as OkStd; };
use std::str::FromStr;
use std::sync::atomic::AtomicBool;
use std::sync::Arc;
use std::time::Duration;
#[link_section = ".rtc.data"] #[link_section = ".rtc.data"]
static mut LAST_WATERING_TIMESTAMP: [i64; PLANT_COUNT] = [0; PLANT_COUNT]; static mut LAST_WATERING_TIMESTAMP: [i64; PLANT_COUNT] = [0; PLANT_COUNT];
@ -60,35 +42,38 @@ pub struct FileSystemSizeInfo {
} }
pub struct MqttClient<'a> { pub struct MqttClient<'a> {
mqtt_client: EspMqttClient<'a>, //mqtt_client: EspMqttClient<'a>,
base_topic: heapless::String<64>, base_topic: heapless::String<64>,
} }
pub struct Esp<'a> { pub struct Esp<'a> {
pub(crate) mqtt_client: Option<MqttClient<'a>>, pub(crate) mqtt_client: Option<MqttClient<'a>>,
pub(crate) wifi_driver: EspWifi<'a>, //pub(crate) wifi_driver: EspWifi<'a>,
pub(crate) boot_button: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, esp_idf_hal::gpio::Input>, //pub(crate) boot_button: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, esp_idf_hal::gpio::Input>,
pub(crate) delay: Delay,
} }
struct AccessPointInfo {}
impl Esp<'_> { impl Esp<'_> {
const SPIFFS_PARTITION_NAME: &'static str = "storage"; const SPIFFS_PARTITION_NAME: &'static str = "storage";
const CONFIG_FILE: &'static str = "/spiffs/config.cfg"; const CONFIG_FILE: &'static str = "/spiffs/config.cfg";
const BASE_PATH: &'static str = "/spiffs"; const BASE_PATH: &'static str = "/spiffs";
pub(crate) fn mode_override_pressed(&mut self) -> bool { pub(crate) fn mode_override_pressed(&mut self) -> bool {
self.boot_button.get_level() == Level::Low todo!();
//self.boot_button.get_level() == Level::Low
} }
pub(crate) fn sntp(&mut self, max_wait_ms: u32) -> anyhow::Result<DateTime<Utc>> { pub(crate) async fn sntp(&mut self, max_wait_ms: u32) -> anyhow::Result<DateTime<Utc>> {
let sntp = sntp::EspSntp::new_default()?; //let sntp = sntp::EspSntp::new_default()?;
let mut counter = 0; //let mut counter = 0;
while sntp.get_sync_status() != SyncStatus::Completed { //while sntp.get_sync_status() != SyncStatus::Completed {
self.delay.delay_ms(100); // self.delay.delay_ms(100);
counter += 100; // counter += 100;
if counter > max_wait_ms { // if counter > max_wait_ms {
bail!("Reached sntp timeout, aborting") // bail!("Reached sntp timeout, aborting")
} // }
} //}
self.time() //self.time()
todo!();
} }
pub(crate) fn time(&mut self) -> anyhow::Result<DateTime<Utc>> { pub(crate) fn time(&mut self) -> anyhow::Result<DateTime<Utc>> {
let time = EspSystemTime {}.now().as_millis(); let time = EspSystemTime {}.now().as_millis();
@ -97,7 +82,8 @@ impl Esp<'_> {
.ok_or(anyhow!("could not convert timestamp"))?; .ok_or(anyhow!("could not convert timestamp"))?;
anyhow::Ok(local_time) anyhow::Ok(local_time)
} }
pub(crate) fn wifi_scan(&mut self) -> anyhow::Result<Vec<AccessPointInfo>> {
pub(crate) async fn wifi_scan(&mut self) -> anyhow::Result<Vec<AccessPointInfo>> {
self.wifi_driver.start_scan( self.wifi_driver.start_scan(
&ScanConfig { &ScanConfig {
scan_type: ScanType::Passive(Duration::from_secs(5)), scan_type: ScanType::Passive(Duration::from_secs(5)),
@ -149,7 +135,7 @@ impl Esp<'_> {
} }
} }
pub(crate) fn wifi_ap(&mut self) -> anyhow::Result<()> { pub(crate) async fn wifi_ap(&mut self) -> anyhow::Result<()> {
let ssid = match self.load_config() { let ssid = match self.load_config() {
Ok(config) => config.network.ap_ssid.clone(), Ok(config) => config.network.ap_ssid.clone(),
Err(_) => heapless::String::from_str("PlantCtrl Emergency Mode").unwrap(), Err(_) => heapless::String::from_str("PlantCtrl Emergency Mode").unwrap(),
@ -167,7 +153,7 @@ impl Esp<'_> {
anyhow::Ok(()) anyhow::Ok(())
} }
pub(crate) fn wifi(&mut self, network_config: &NetworkConfig) -> anyhow::Result<IpInfo> { pub(crate) async fn wifi(&mut self, network_config: &NetworkConfig) -> anyhow::Result<IpInfo> {
let ssid = network_config let ssid = network_config
.ssid .ssid
.clone() .clone()
@ -212,7 +198,7 @@ impl Esp<'_> {
bail!("Did not manage wifi connection within timeout"); bail!("Did not manage wifi connection within timeout");
} }
} }
println!("Should be connected now, waiting for link to be up"); log::info!("Should be connected now, waiting for link to be up");
while !self.wifi_driver.is_up()? { while !self.wifi_driver.is_up()? {
delay.delay_ms(250); delay.delay_ms(250);
@ -229,31 +215,37 @@ impl Esp<'_> {
log(LogMessage::WifiInfo, 0, 0, "", &format!("{address:?}")); log(LogMessage::WifiInfo, 0, 0, "", &format!("{address:?}"));
anyhow::Ok(address) anyhow::Ok(address)
} }
pub(crate) fn load_config(&mut self) -> anyhow::Result<PlantControllerConfig> { pub(crate) async fn load_config(&mut self) -> anyhow::Result<PlantControllerConfig> {
let cfg = File::open(Self::CONFIG_FILE)?; let cfg = File::open(Self::CONFIG_FILE)?;
let config: PlantControllerConfig = serde_json::from_reader(cfg)?; let config: PlantControllerConfig = serde_json::from_reader(cfg)?;
anyhow::Ok(config) anyhow::Ok(config)
} }
pub(crate) fn save_config(&mut self, config: &PlantControllerConfig) -> anyhow::Result<()> { pub(crate) async fn save_config(
&mut self,
config: &PlantControllerConfig,
) -> anyhow::Result<()> {
let mut cfg = File::create(Self::CONFIG_FILE)?; let mut cfg = File::create(Self::CONFIG_FILE)?;
serde_json::to_writer(&mut cfg, &config)?; serde_json::to_writer(&mut cfg, &config)?;
println!("Wrote config config {:?}", config); log::info!("Wrote config config {:?}", config);
anyhow::Ok(()) anyhow::Ok(())
} }
pub(crate) fn mount_file_system(&mut self) -> anyhow::Result<()> { pub(crate) async fn mount_file_system(&mut self) -> anyhow::Result<()> {
log(LogMessage::MountingFilesystem, 0, 0, "", ""); log(LogMessage::MountingFilesystem, 0, 0, "", "");
let base_path = CString::new("/spiffs")?; let base_path = String::try_from("/spiffs")?;
let storage = CString::new(Self::SPIFFS_PARTITION_NAME)?; let storage = String::try_from(Self::SPIFFS_PARTITION_NAME)?;
let conf = esp_idf_sys::esp_vfs_spiffs_conf_t { let conf = todo!();
base_path: base_path.as_ptr(),
partition_label: storage.as_ptr(),
max_files: 5,
format_if_mount_failed: true,
};
unsafe { //let conf = esp_idf_sys::esp_vfs_spiffs_conf_t {
esp_idf_sys::esp!(esp_idf_sys::esp_vfs_spiffs_register(&conf))?; //base_path: base_path.as_ptr(),
} //partition_label: storage.as_ptr(),
//max_files: 5,
//format_if_mount_failed: true,
//};
//TODO
//unsafe {
//esp_idf_sys::esp!(esp_idf_sys::esp_vfs_spiffs_register(&conf))?;
//}
let free_space = self.file_system_size()?; let free_space = self.file_system_size()?;
log( log(
@ -265,7 +257,7 @@ impl Esp<'_> {
); );
anyhow::Ok(()) anyhow::Ok(())
} }
fn file_system_size(&mut self) -> anyhow::Result<FileSystemSizeInfo> { async fn file_system_size(&mut self) -> anyhow::Result<FileSystemSizeInfo> {
let storage = CString::new(Self::SPIFFS_PARTITION_NAME)?; let storage = CString::new(Self::SPIFFS_PARTITION_NAME)?;
let mut total_size = 0; let mut total_size = 0;
let mut used_size = 0; let mut used_size = 0;
@ -283,7 +275,7 @@ impl Esp<'_> {
}) })
} }
pub(crate) fn list_files(&self) -> FileList { pub(crate) async fn list_files(&self) -> FileList {
let storage = CString::new(Self::SPIFFS_PARTITION_NAME).unwrap(); let storage = CString::new(Self::SPIFFS_PARTITION_NAME).unwrap();
let mut file_system_corrupt = None; let mut file_system_corrupt = None;
@ -330,7 +322,7 @@ impl Esp<'_> {
iter_error, iter_error,
} }
} }
pub(crate) fn delete_file(&self, filename: &str) -> anyhow::Result<()> { pub(crate) async fn delete_file(&self, filename: &str) -> anyhow::Result<()> {
let filepath = Path::new(Self::BASE_PATH).join(Path::new(filename)); let filepath = Path::new(Self::BASE_PATH).join(Path::new(filename));
match fs::remove_file(filepath) { match fs::remove_file(filepath) {
OkStd(_) => anyhow::Ok(()), OkStd(_) => anyhow::Ok(()),
@ -339,7 +331,11 @@ impl Esp<'_> {
} }
} }
} }
pub(crate) fn get_file_handle(&self, filename: &str, write: bool) -> anyhow::Result<File> { pub(crate) async fn get_file_handle(
&self,
filename: &str,
write: bool,
) -> anyhow::Result<File> {
let filepath = Path::new(Self::BASE_PATH).join(Path::new(filename)); let filepath = Path::new(Self::BASE_PATH).join(Path::new(filename));
anyhow::Ok(if write { anyhow::Ok(if write {
File::create(filepath)? File::create(filepath)?
@ -377,22 +373,24 @@ impl Esp<'_> {
"", "",
); );
for i in 0..PLANT_COUNT { for i in 0..PLANT_COUNT {
println!( log::info!(
"LAST_WATERING_TIMESTAMP[{}] = UTC {}", "LAST_WATERING_TIMESTAMP[{}] = UTC {}",
i, LAST_WATERING_TIMESTAMP[i] i,
LAST_WATERING_TIMESTAMP[i]
); );
} }
for i in 0..PLANT_COUNT { for i in 0..PLANT_COUNT {
println!( log::info!(
"CONSECUTIVE_WATERING_PLANT[{}] = {}", "CONSECUTIVE_WATERING_PLANT[{}] = {}",
i, CONSECUTIVE_WATERING_PLANT[i] i,
CONSECUTIVE_WATERING_PLANT[i]
); );
} }
} }
} }
} }
pub(crate) fn mqtt(&mut self, network_config: &NetworkConfig) -> anyhow::Result<()> { pub(crate) async fn mqtt(&mut self, network_config: &NetworkConfig) -> anyhow::Result<()> {
let base_topic = network_config let base_topic = network_config
.base_topic .base_topic
.as_ref() .as_ref()
@ -468,35 +466,35 @@ impl Esp<'_> {
mqtt_connected_event_received_copy mqtt_connected_event_received_copy
.store(true, std::sync::atomic::Ordering::Relaxed); .store(true, std::sync::atomic::Ordering::Relaxed);
mqtt_connected_event_ok_copy.store(true, std::sync::atomic::Ordering::Relaxed); mqtt_connected_event_ok_copy.store(true, std::sync::atomic::Ordering::Relaxed);
println!("Mqtt connected"); log::info!("Mqtt connected");
} }
esp_idf_svc::mqtt::client::EventPayload::Disconnected => { esp_idf_svc::mqtt::client::EventPayload::Disconnected => {
mqtt_connected_event_received_copy mqtt_connected_event_received_copy
.store(true, std::sync::atomic::Ordering::Relaxed); .store(true, std::sync::atomic::Ordering::Relaxed);
mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed); mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed);
println!("Mqtt disconnected"); log::info!("Mqtt disconnected");
} }
esp_idf_svc::mqtt::client::EventPayload::Error(esp_error) => { esp_idf_svc::mqtt::client::EventPayload::Error(esp_error) => {
println!("EspMqttError reported {:?}", esp_error); log::info!("EspMqttError reported {:?}", esp_error);
mqtt_connected_event_received_copy mqtt_connected_event_received_copy
.store(true, std::sync::atomic::Ordering::Relaxed); .store(true, std::sync::atomic::Ordering::Relaxed);
mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed); mqtt_connected_event_ok_copy.store(false, std::sync::atomic::Ordering::Relaxed);
println!("Mqtt error"); log::info!("Mqtt error");
} }
esp_idf_svc::mqtt::client::EventPayload::BeforeConnect => { esp_idf_svc::mqtt::client::EventPayload::BeforeConnect => {
println!("Mqtt before connect") log::info!("Mqtt before connect")
} }
esp_idf_svc::mqtt::client::EventPayload::Subscribed(_) => { esp_idf_svc::mqtt::client::EventPayload::Subscribed(_) => {
println!("Mqtt subscribed") log::info!("Mqtt subscribed")
} }
esp_idf_svc::mqtt::client::EventPayload::Unsubscribed(_) => { esp_idf_svc::mqtt::client::EventPayload::Unsubscribed(_) => {
println!("Mqtt unsubscribed") log::info!("Mqtt unsubscribed")
} }
esp_idf_svc::mqtt::client::EventPayload::Published(_) => { esp_idf_svc::mqtt::client::EventPayload::Published(_) => {
println!("Mqtt published") log::info!("Mqtt published")
} }
esp_idf_svc::mqtt::client::EventPayload::Deleted(_) => { esp_idf_svc::mqtt::client::EventPayload::Deleted(_) => {
println!("Mqtt deleted") log::info!("Mqtt deleted")
} }
} }
})?; })?;
@ -506,10 +504,12 @@ impl Esp<'_> {
wait_for_connections_event += 1; wait_for_connections_event += 1;
match mqtt_connected_event_received.load(std::sync::atomic::Ordering::Relaxed) { match mqtt_connected_event_received.load(std::sync::atomic::Ordering::Relaxed) {
true => { true => {
println!("Mqtt connection callback received, progressing"); log::info!("Mqtt connection callback received, progressing");
match mqtt_connected_event_ok.load(std::sync::atomic::Ordering::Relaxed) { match mqtt_connected_event_ok.load(std::sync::atomic::Ordering::Relaxed) {
true => { true => {
println!("Mqtt did callback as connected, testing with roundtrip now"); log::info!(
"Mqtt did callback as connected, testing with roundtrip now"
);
//subscribe to roundtrip //subscribe to roundtrip
client.subscribe(round_trip_topic.as_str(), ExactlyOnce)?; client.subscribe(round_trip_topic.as_str(), ExactlyOnce)?;
client.subscribe(stay_alive_topic.as_str(), ExactlyOnce)?; client.subscribe(stay_alive_topic.as_str(), ExactlyOnce)?;
@ -526,7 +526,7 @@ impl Esp<'_> {
wait_for_roundtrip += 1; wait_for_roundtrip += 1;
match round_trip_ok.load(std::sync::atomic::Ordering::Relaxed) { match round_trip_ok.load(std::sync::atomic::Ordering::Relaxed) {
true => { true => {
println!("Round trip registered, proceeding"); log::info!("Round trip registered, proceeding");
self.mqtt_client = Some(MqttClient { self.mqtt_client = Some(MqttClient {
mqtt_client: client, mqtt_client: client,
base_topic: base_topic_copy, base_topic: base_topic_copy,
@ -552,26 +552,30 @@ impl Esp<'_> {
} }
bail!("Mqtt did not fire connection callback in time"); bail!("Mqtt did not fire connection callback in time");
} }
pub(crate) fn mqtt_publish(&mut self, subtopic: &str, message: &[u8]) -> anyhow::Result<()> { pub(crate) async fn mqtt_publish(
&mut self,
subtopic: &str,
message: &[u8],
) -> anyhow::Result<()> {
if self.mqtt_client.is_none() { if self.mqtt_client.is_none() {
return anyhow::Ok(()); return anyhow::Ok(());
} }
if !subtopic.starts_with("/") { if !subtopic.starts_with("/") {
println!("Subtopic without / at start {}", subtopic); log::info!("Subtopic without / at start {}", subtopic);
bail!("Subtopic without / at start {}", subtopic); bail!("Subtopic without / at start {}", subtopic);
} }
if subtopic.len() > 192 { if subtopic.len() > 192 {
println!("Subtopic exceeds 192 chars {}", subtopic); log::info!("Subtopic exceeds 192 chars {}", subtopic);
bail!("Subtopic exceeds 192 chars {}", subtopic); bail!("Subtopic exceeds 192 chars {}", subtopic);
} }
let client = self.mqtt_client.as_mut().unwrap(); let client = self.mqtt_client.as_mut().unwrap();
let mut full_topic: heapless::String<256> = heapless::String::new(); let mut full_topic: heapless::String<256> = heapless::String::new();
if full_topic.push_str(client.base_topic.as_str()).is_err() { if full_topic.push_str(client.base_topic.as_str()).is_err() {
println!("Some error assembling full_topic 1"); log::info!("Some error assembling full_topic 1");
bail!("Some error assembling full_topic 1") bail!("Some error assembling full_topic 1")
}; };
if full_topic.push_str(subtopic).is_err() { if full_topic.push_str(subtopic).is_err() {
println!("Some error assembling full_topic 2"); log::info!("Some error assembling full_topic 2");
bail!("Some error assembling full_topic 2") bail!("Some error assembling full_topic 2")
}; };
let publish = client let publish = client
@ -580,7 +584,7 @@ impl Esp<'_> {
Delay::new(10).delay_ms(50); Delay::new(10).delay_ms(50);
match publish { match publish {
OkStd(message_id) => { OkStd(message_id) => {
println!( log::info!(
"Published mqtt topic {} with message {:#?} msgid is {:?}", "Published mqtt topic {} with message {:#?} msgid is {:?}",
full_topic, full_topic,
String::from_utf8_lossy(message), String::from_utf8_lossy(message),
@ -589,7 +593,7 @@ impl Esp<'_> {
anyhow::Ok(()) anyhow::Ok(())
} }
Err(err) => { Err(err) => {
println!( log::info!(
"Error during mqtt send on topic {} with message {:#?} error is {:?}", "Error during mqtt send on topic {} with message {:#?} error is {:?}",
full_topic, full_topic,
String::from_utf8_lossy(message), String::from_utf8_lossy(message),

View File

@ -9,9 +9,8 @@ use crate::{
use anyhow::{bail, Result}; use anyhow::{bail, Result};
use chrono::{DateTime, Utc}; use chrono::{DateTime, Utc};
use embedded_hal::digital::OutputPin; use embedded_hal::digital::OutputPin;
use esp_idf_hal::gpio::{IOPin, Pull};
use esp_idf_hal::gpio::{InputOutput, PinDriver};
use measurements::{Current, Voltage}; use measurements::{Current, Voltage};
use crate::alloc::boxed::Box;
pub struct Initial<'a> { pub struct Initial<'a> {
pub(crate) general_fault: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>, pub(crate) general_fault: PinDriver<'a, esp_idf_hal::gpio::AnyIOPin, InputOutput>,
@ -51,7 +50,7 @@ pub(crate) fn create_initial_board(
config: PlantControllerConfig, config: PlantControllerConfig,
esp: Esp<'static>, esp: Esp<'static>,
) -> Result<Box<dyn BoardInteraction<'static> + Send>> { ) -> Result<Box<dyn BoardInteraction<'static> + Send>> {
println!("Start initial"); log::info!("Start initial");
let mut general_fault = PinDriver::input_output(free_pins.gpio6.downgrade())?; let mut general_fault = PinDriver::input_output(free_pins.gpio6.downgrade())?;
general_fault.set_pull(Pull::Floating)?; general_fault.set_pull(Pull::Floating)?;
general_fault.set_low()?; general_fault.set_low()?;

View File

@ -4,9 +4,10 @@ mod initial_hal;
mod rtc; mod rtc;
mod v3_hal; mod v3_hal;
mod v4_hal; mod v4_hal;
mod water;
mod v4_sensor; mod v4_sensor;
mod water;
use crate::alloc::string::ToString;
use crate::hal::rtc::{DS3231Module, RTCModuleInteraction}; use crate::hal::rtc::{DS3231Module, RTCModuleInteraction};
use crate::hal::water::TankSensor; use crate::hal::water::TankSensor;
use crate::{ use crate::{
@ -17,12 +18,18 @@ use crate::{
}, },
log::{log, LogMessage}, log::{log, LogMessage},
}; };
use alloc::boxed::Box;
use anyhow::{Ok, Result}; use anyhow::{Ok, Result};
use async_trait::async_trait;
use battery::BQ34Z100G1; use battery::BQ34Z100G1;
use bq34z100::Bq34z100g1Driver; use bq34z100::Bq34z100g1Driver;
use ds323x::{DateTimeAccess, Ds323x}; use ds323x::{DateTimeAccess, Ds323x};
use eeprom24x::{Eeprom24x, SlaveAddr, Storage}; use eeprom24x::{Eeprom24x, SlaveAddr, Storage};
use embassy_sync::blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex};
use embassy_sync::mutex::Mutex;
use embassy_sync::{LazyLock, Mutex};
use embedded_hal_bus::i2c::MutexDevice; use embedded_hal_bus::i2c::MutexDevice;
use esp_idf_hal::can::CAN;
use esp_idf_hal::pcnt::PCNT1; use esp_idf_hal::pcnt::PCNT1;
use esp_idf_hal::{ use esp_idf_hal::{
adc::ADC1, adc::ADC1,
@ -45,18 +52,13 @@ use esp_idf_sys::{
}; };
use esp_ota::mark_app_valid; use esp_ota::mark_app_valid;
use measurements::{Current, Voltage}; use measurements::{Current, Voltage};
use once_cell::sync::Lazy;
use std::result::Result::Ok as OkStd;
use std::sync::Mutex;
use std::time::Duration;
use esp_idf_hal::can::CAN;
//Only support for 8 right now! //Only support for 8 right now!
pub const PLANT_COUNT: usize = 8; pub const PLANT_COUNT: usize = 8;
const TANK_MULTI_SAMPLE: usize = 11; const TANK_MULTI_SAMPLE: usize = 11;
pub static I2C_DRIVER: Lazy<Mutex<I2cDriver<'static>>> = Lazy::new(PlantHal::create_i2c); pub static I2C_DRIVER: LazyLock<Mutex<I2cDriver<'static>>> = LazyLock::new(PlantHal::create_i2c);
fn deep_sleep(duration_in_ms: u64) -> ! { fn deep_sleep(duration_in_ms: u64) -> ! {
unsafe { unsafe {
@ -88,8 +90,9 @@ pub struct HAL<'a> {
pub board_hal: Box<dyn BoardInteraction<'a> + Send>, pub board_hal: Box<dyn BoardInteraction<'a> + Send>,
} }
#[async_trait]
pub trait BoardInteraction<'a> { pub trait BoardInteraction<'a> {
fn get_tank_sensor(&mut self) -> Option<&mut TankSensor<'a>>; fn get_tank_sensor(&mut self) -> Option<&mut TankSensor>;
fn get_esp(&mut self) -> &mut Esp<'a>; fn get_esp(&mut self) -> &mut Esp<'a>;
fn get_config(&mut self) -> &PlantControllerConfig; fn get_config(&mut self) -> &PlantControllerConfig;
fn get_battery_monitor(&mut self) -> &mut Box<dyn BatteryInteraction + Send>; fn get_battery_monitor(&mut self) -> &mut Box<dyn BatteryInteraction + Send>;
@ -100,20 +103,20 @@ pub trait BoardInteraction<'a> {
fn is_day(&self) -> bool; fn is_day(&self) -> bool;
//should be multsampled //should be multsampled
fn light(&mut self, enable: bool) -> Result<()>; fn light(&mut self, enable: bool) -> Result<()>;
fn pump(&mut self, plant: usize, enable: bool) -> Result<()>; async fn pump(&mut self, plant: usize, enable: bool) -> Result<()>;
fn pump_current(&mut self, plant: usize) -> Result<Current>; async fn pump_current(&mut self, plant: usize) -> Result<Current>;
fn fault(&mut self, plant: usize, enable: bool) -> Result<()>; async fn fault(&mut self, plant: usize, enable: bool) -> Result<()>;
fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> Result<f32>; async fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> Result<f32>;
fn general_fault(&mut self, enable: bool); async fn general_fault(&mut self, enable: bool);
fn test(&mut self) -> Result<()>; async fn test(&mut self) -> Result<()>;
fn set_config(&mut self, config: PlantControllerConfig) -> Result<()>; async fn set_config(&mut self, config: PlantControllerConfig) -> Result<()>;
fn get_mptt_voltage(&mut self) -> anyhow::Result<Voltage>; async fn get_mptt_voltage(&mut self) -> anyhow::Result<Voltage>;
fn get_mptt_current(&mut self) -> anyhow::Result<Current>; async fn get_mptt_current(&mut self) -> anyhow::Result<Current>;
} }
impl dyn BoardInteraction<'_> { impl dyn BoardInteraction<'_> {
//the counter is just some arbitrary number that increases whenever some progress was made, try to keep the updates < 10 per second for ux reasons //the counter is just some arbitrary number that increases whenever some progress was made, try to keep the updates < 10 per second for ux reasons
fn _progress(&mut self, counter: u32) { async fn _progress(&mut self, counter: u32) {
let even = counter % 2 == 0; let even = counter % 2 == 0;
let current = counter / (PLANT_COUNT as u32); let current = counter / (PLANT_COUNT as u32);
for led in 0..PLANT_COUNT { for led in 0..PLANT_COUNT {
@ -178,7 +181,7 @@ impl PlantHal {
Mutex::new(I2cDriver::new(i2c, sda, scl, &config).unwrap()) Mutex::new(I2cDriver::new(i2c, sda, scl, &config).unwrap())
} }
pub fn create() -> Result<Mutex<HAL<'static>>> { pub fn create() -> Result<Mutex<CriticalSectionRawMutex, HAL<'static>>> {
let peripherals = Peripherals::take()?; let peripherals = Peripherals::take()?;
let sys_loop = EspSystemEventLoop::take()?; let sys_loop = EspSystemEventLoop::take()?;
let nvs = EspDefaultNvsPartition::take()?; let nvs = EspDefaultNvsPartition::take()?;
@ -266,10 +269,10 @@ impl PlantHal {
let config = esp.load_config(); let config = esp.load_config();
println!("Init rtc driver"); log::info!("Init rtc driver");
let mut rtc = Ds323x::new_ds3231(MutexDevice::new(&I2C_DRIVER)); let mut rtc = Ds323x::new_ds3231(MutexDevice::new(&I2C_DRIVER));
println!("Init rtc eeprom driver"); log::info!("Init rtc eeprom driver");
let eeprom = { let eeprom = {
Eeprom24x::new_24x32( Eeprom24x::new_24x32(
MutexDevice::new(&I2C_DRIVER), MutexDevice::new(&I2C_DRIVER),
@ -279,10 +282,10 @@ impl PlantHal {
let rtc_time = rtc.datetime(); let rtc_time = rtc.datetime();
match rtc_time { match rtc_time {
OkStd(tt) => { OkStd(tt) => {
println!("Rtc Module reports time at UTC {}", tt); log::info!("Rtc Module reports time at UTC {}", tt);
} }
Err(err) => { Err(err) => {
println!("Rtc Module could not be read {:?}", err); log::info!("Rtc Module could not be read {:?}", err);
} }
} }

View File

@ -1,4 +1,7 @@
use crate::hal::Box;
use alloc::vec::Vec;
use anyhow::{anyhow, bail}; use anyhow::{anyhow, bail};
use async_trait::async_trait;
use bincode::config::Configuration; use bincode::config::Configuration;
use bincode::{config, Decode, Encode}; use bincode::{config, Decode, Encode};
use chrono::{DateTime, Utc}; use chrono::{DateTime, Utc};
@ -7,23 +10,20 @@ use eeprom24x::addr_size::TwoBytes;
use eeprom24x::page_size::B32; use eeprom24x::page_size::B32;
use eeprom24x::unique_serial::No; use eeprom24x::unique_serial::No;
use eeprom24x::Storage; use eeprom24x::Storage;
use embedded_hal_bus::i2c::MutexDevice;
use embedded_storage::ReadStorage as embedded_storage_ReadStorage; use embedded_storage::ReadStorage as embedded_storage_ReadStorage;
use embedded_storage::Storage as embedded_storage_Storage; use embedded_storage::Storage as embedded_storage_Storage;
use esp_idf_hal::delay::Delay;
use esp_idf_hal::i2c::I2cDriver;
use serde::{Deserialize, Serialize}; use serde::{Deserialize, Serialize};
use std::result::Result::Ok as OkStd;
const X25: crc::Crc<u16> = crc::Crc::<u16>::new(&crc::CRC_16_IBM_SDLC); const X25: crc::Crc<u16> = crc::Crc::<u16>::new(&crc::CRC_16_IBM_SDLC);
const CONFIG: Configuration = config::standard(); const CONFIG: Configuration = config::standard();
#[async_trait]
pub trait RTCModuleInteraction { pub trait RTCModuleInteraction {
fn get_backup_info(&mut self) -> anyhow::Result<BackupHeader>; async fn get_backup_info(&mut self) -> anyhow::Result<BackupHeader>;
fn get_backup_config(&mut self) -> anyhow::Result<Vec<u8>>; async fn get_backup_config(&mut self) -> anyhow::Result<Vec<u8>>;
fn backup_config(&mut self, bytes: &[u8]) -> anyhow::Result<()>; async fn backup_config(&mut self, bytes: &[u8]) -> anyhow::Result<()>;
fn get_rtc_time(&mut self) -> anyhow::Result<DateTime<Utc>>; async fn get_rtc_time(&mut self) -> anyhow::Result<DateTime<Utc>>;
fn set_rtc_time(&mut self, time: &DateTime<Utc>) -> anyhow::Result<()>; async fn set_rtc_time(&mut self, time: &DateTime<Utc>) -> anyhow::Result<()>;
} }
const BACKUP_HEADER_MAX_SIZE: usize = 64; const BACKUP_HEADER_MAX_SIZE: usize = 64;
@ -52,7 +52,7 @@ impl RTCModuleInteraction for DS3231Module<'_> {
let (header, len): (BackupHeader, usize) = let (header, len): (BackupHeader, usize) =
bincode::decode_from_slice(&header_page_buffer[..], CONFIG)?; bincode::decode_from_slice(&header_page_buffer[..], CONFIG)?;
println!("Raw header is {:?} with size {}", header_page_buffer, len); log::info!("Raw header is {:?} with size {}", header_page_buffer, len);
anyhow::Ok(header) anyhow::Ok(header)
} }
@ -95,9 +95,10 @@ impl RTCModuleInteraction for DS3231Module<'_> {
}; };
let config = config::standard(); let config = config::standard();
let encoded = bincode::encode_into_slice(&header, &mut header_page_buffer, config)?; let encoded = bincode::encode_into_slice(&header, &mut header_page_buffer, config)?;
println!( log::info!(
"Raw header is {:?} with size {}", "Raw header is {:?} with size {}",
header_page_buffer, encoded header_page_buffer,
encoded
); );
self.storage self.storage
.write(0, &header_page_buffer) .write(0, &header_page_buffer)

View File

@ -10,14 +10,12 @@ use crate::{
}; };
use anyhow::{bail, Ok, Result}; use anyhow::{bail, Ok, Result};
use embedded_hal::digital::OutputPin; use embedded_hal::digital::OutputPin;
use esp_idf_hal::{
gpio::{AnyInputPin, IOPin, InputOutput, PinDriver, Pull},
pcnt::{PcntChannel, PcntChannelConfig, PcntControlMode, PcntCountMode, PcntDriver, PinIndex},
};
use esp_idf_sys::{gpio_hold_dis, gpio_hold_en};
use measurements::{Current, Voltage}; use measurements::{Current, Voltage};
use plant_ctrl2::sipo::ShiftRegister40; use plant_ctrl2::sipo::ShiftRegister40;
use std::result::Result::Ok as OkStd; 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 PUMP8_BIT: usize = 0;
const PUMP1_BIT: usize = 1; const PUMP1_BIT: usize = 1;
@ -94,7 +92,7 @@ pub(crate) fn create_v3(
battery_monitor: Box<dyn BatteryInteraction + Send>, battery_monitor: Box<dyn BatteryInteraction + Send>,
rtc_module: Box<dyn RTCModuleInteraction + Send>, rtc_module: Box<dyn RTCModuleInteraction + Send>,
) -> Result<Box<dyn BoardInteraction<'static> + Send>> { ) -> Result<Box<dyn BoardInteraction<'static> + Send>> {
println!("Start v3"); log::info!("Start v3");
let mut clock = PinDriver::input_output(peripherals.gpio15.downgrade())?; let mut clock = PinDriver::input_output(peripherals.gpio15.downgrade())?;
clock.set_pull(Pull::Floating)?; clock.set_pull(Pull::Floating)?;
let mut latch = PinDriver::input_output(peripherals.gpio3.downgrade())?; let mut latch = PinDriver::input_output(peripherals.gpio3.downgrade())?;

View File

@ -12,12 +12,6 @@ use crate::log::{log, LogMessage};
use anyhow::bail; use anyhow::bail;
use embedded_hal::digital::OutputPin; use embedded_hal::digital::OutputPin;
use embedded_hal_bus::i2c::MutexDevice; use embedded_hal_bus::i2c::MutexDevice;
use esp_idf_hal::gpio::{AnyInputPin, IOPin, InputOutput, Output, PinDriver, Pull};
use esp_idf_hal::i2c::I2cDriver;
use esp_idf_hal::pcnt::{
PcntChannel, PcntChannelConfig, PcntControlMode, PcntCountMode, PcntDriver, PinIndex,
};
use esp_idf_sys::{gpio_hold_dis, gpio_hold_en};
use ina219::address::{Address, Pin}; use ina219::address::{Address, Pin};
use ina219::calibration::UnCalibrated; use ina219::calibration::UnCalibrated;
use ina219::configuration::{Configuration, OperatingMode}; use ina219::configuration::{Configuration, OperatingMode};
@ -27,7 +21,9 @@ use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface};
use std::result::Result::Ok as OkStd; use std::result::Result::Ok as OkStd;
use embedded_can::Frame; use embedded_can::Frame;
use embedded_can::StandardId; use embedded_can::StandardId;
use esp_idf_hal::can; use alloc::string::ToString;
use alloc::boxed::Box;
use esp_hal::gpio::Pull;
pub enum Charger<'a> { pub enum Charger<'a> {
SolarMpptV1 { SolarMpptV1 {
@ -52,7 +48,7 @@ impl Charger<'_> {
operating_mode: OperatingMode::PowerDown, operating_mode: OperatingMode::PowerDown,
}) })
.map_err(|e| { .map_err(|e| {
println!( log::info!(
"Error setting ina mppt configuration during deep sleep preparation{:?}", "Error setting ina mppt configuration during deep sleep preparation{:?}",
e e
); );
@ -133,7 +129,7 @@ pub(crate) fn create_v4(
battery_monitor: Box<dyn BatteryInteraction + Send>, battery_monitor: Box<dyn BatteryInteraction + Send>,
rtc_module: Box<dyn RTCModuleInteraction + Send>, rtc_module: Box<dyn RTCModuleInteraction + Send>,
) -> anyhow::Result<Box<dyn BoardInteraction<'static> + Send + 'static>> { ) -> anyhow::Result<Box<dyn BoardInteraction<'static> + Send + 'static>> {
println!("Start v4"); log::info!("Start v4");
let mut awake = PinDriver::output(peripherals.gpio21.downgrade())?; let mut awake = PinDriver::output(peripherals.gpio21.downgrade())?;
awake.set_high()?; awake.set_high()?;
@ -163,7 +159,7 @@ pub(crate) fn create_v4(
let mut sensor_expander = Pca9535Immediate::new(MutexDevice::new(&I2C_DRIVER), 34); let mut sensor_expander = Pca9535Immediate::new(MutexDevice::new(&I2C_DRIVER), 34);
let sensor = match sensor_expander.pin_into_output(GPIOBank::Bank0, 0) { let sensor = match sensor_expander.pin_into_output(GPIOBank::Bank0, 0) {
Ok(_) => { Ok(_) => {
println!("SensorExpander answered"); log::info!("SensorExpander answered");
//pulse counter version //pulse counter version
let mut signal_counter = PcntDriver::new( let mut signal_counter = PcntDriver::new(
peripherals.pcnt0, peripherals.pcnt0,
@ -200,7 +196,7 @@ pub(crate) fn create_v4(
} }
} }
Err(_) => { Err(_) => {
println!("Can bus mode "); log::info!("Can bus mode ");
let timing = can::config::Timing::B25K; let timing = can::config::Timing::B25K;
let config = can::config::Config::new().timing(timing); let config = can::config::Config::new().timing(timing);
let can = can::CanDriver::new(peripherals.can, peripherals.gpio0, peripherals.gpio2, &config).unwrap(); let can = can::CanDriver::new(peripherals.can, peripherals.gpio0, peripherals.gpio2, &config).unwrap();
@ -211,7 +207,7 @@ pub(crate) fn create_v4(
can.transmit(&tx_frame, 1000).unwrap(); can.transmit(&tx_frame, 1000).unwrap();
if let Ok(rx_frame) = can.receive(1000) { if let Ok(rx_frame) = can.receive(1000) {
println!("rx {:}:", rx_frame); log::info!("rx {:}:", rx_frame);
} }
//can bus version //can bus version
SensorImpl::CanBus { SensorImpl::CanBus {
@ -274,7 +270,7 @@ pub(crate) fn create_v4(
) { ) {
Ok(pump_ina) => Some(pump_ina), Ok(pump_ina) => Some(pump_ina),
Err(err) => { Err(err) => {
println!("Error creating pump ina: {:?}", err); log::info!("Error creating pump ina: {:?}", err);
None None
} }
}; };

View File

@ -1,16 +1,17 @@
use crate::hal::Sensor;
use crate::log::{log, LogMessage};
use alloc::string::ToString;
use embedded_hal_bus::i2c::MutexDevice; use embedded_hal_bus::i2c::MutexDevice;
use esp_idf_hal::can::CanDriver; use esp_idf_hal::can::CanDriver;
use esp_idf_hal::delay::Delay; use esp_idf_hal::delay::Delay;
use esp_idf_hal::i2c::I2cDriver; use esp_idf_hal::i2c::I2cDriver;
use esp_idf_hal::pcnt::PcntDriver; use esp_idf_hal::pcnt::PcntDriver;
use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface}; use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface};
use crate::hal::Sensor;
use crate::log::{log, LogMessage};
const REPEAT_MOIST_MEASURE: usize = 10; const REPEAT_MOIST_MEASURE: usize = 10;
pub trait SensorInteraction { pub trait SensorInteraction {
fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> anyhow::Result<f32>; async fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> anyhow::Result<f32>;
} }
const MS0: u8 = 1_u8; const MS0: u8 = 1_u8;
@ -21,19 +22,23 @@ const MS4: u8 = 2_u8;
const SENSOR_ON: u8 = 5_u8; const SENSOR_ON: u8 = 5_u8;
pub enum SensorImpl<'a> { pub enum SensorImpl<'a> {
PulseCounter{ PulseCounter {
signal_counter: PcntDriver<'a>, signal_counter: PcntDriver<'a>,
sensor_expander: Pca9535Immediate<MutexDevice<'a, I2cDriver<'a>>>, sensor_expander: Pca9535Immediate<MutexDevice<'a, I2cDriver<'a>>>,
}, },
CanBus{ CanBus {
can: CanDriver<'a> can: CanDriver<'a>,
} },
} }
impl SensorInteraction for SensorImpl<'_> { impl SensorInteraction for SensorImpl<'_> {
fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> anyhow::Result<f32> { fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> anyhow::Result<f32> {
match self { match self {
SensorImpl::PulseCounter { signal_counter, sensor_expander, .. } => { SensorImpl::PulseCounter {
signal_counter,
sensor_expander,
..
} => {
let mut results = [0_f32; REPEAT_MOIST_MEASURE]; let mut results = [0_f32; REPEAT_MOIST_MEASURE];
for repeat in 0..REPEAT_MOIST_MEASURE { for repeat in 0..REPEAT_MOIST_MEASURE {
signal_counter.counter_pause()?; signal_counter.counter_pause()?;
@ -70,8 +75,7 @@ impl SensorInteraction for SensorImpl<'_> {
} }
sensor_expander.pin_set_low(GPIOBank::Bank0, MS4)?; sensor_expander.pin_set_low(GPIOBank::Bank0, MS4)?;
sensor_expander sensor_expander.pin_set_high(GPIOBank::Bank0, SENSOR_ON)?;
.pin_set_high(GPIOBank::Bank0, SENSOR_ON)?;
let delay = Delay::new_default(); let delay = Delay::new_default();
let measurement = 100; // TODO what is this scaling factor? what is its purpose? let measurement = 100; // TODO what is this scaling factor? what is its purpose?
@ -83,8 +87,7 @@ impl SensorInteraction for SensorImpl<'_> {
delay.delay_ms(measurement); delay.delay_ms(measurement);
signal_counter.counter_pause()?; signal_counter.counter_pause()?;
sensor_expander.pin_set_high(GPIOBank::Bank0, MS4)?; sensor_expander.pin_set_high(GPIOBank::Bank0, MS4)?;
sensor_expander sensor_expander.pin_set_low(GPIOBank::Bank0, SENSOR_ON)?;
.pin_set_low(GPIOBank::Bank0, SENSOR_ON)?;
sensor_expander.pin_set_low(GPIOBank::Bank0, MS0)?; sensor_expander.pin_set_low(GPIOBank::Bank0, MS0)?;
sensor_expander.pin_set_low(GPIOBank::Bank0, MS1)?; sensor_expander.pin_set_low(GPIOBank::Bank0, MS1)?;
sensor_expander.pin_set_low(GPIOBank::Bank0, MS2)?; sensor_expander.pin_set_low(GPIOBank::Bank0, MS2)?;

View File

@ -102,18 +102,18 @@ impl<'a> TankSensor<'a> {
self.get_flow_meter_value() self.get_flow_meter_value()
} }
pub fn water_temperature_c(&mut self) -> anyhow::Result<f32> { pub async fn water_temperature_c(&mut self) -> anyhow::Result<f32> {
//multisample should be moved to water_temperature_c //multisample should be moved to water_temperature_c
let mut attempt = 1; let mut attempt = 1;
let water_temp: Result<f32, anyhow::Error> = loop { let water_temp: Result<f32, anyhow::Error> = loop {
let temp = self.single_temperature_c(); let temp = self.single_temperature_c();
match &temp { match &temp {
Ok(res) => { Ok(res) => {
println!("Water temp is {}", res); log::info!("Water temp is {}", res);
break temp; break temp;
} }
Err(err) => { Err(err) => {
println!("Could not get water temp {} attempt {}", err, attempt) log::info!("Could not get water temp {} attempt {}", err, attempt)
} }
} }
if attempt == 5 { if attempt == 5 {
@ -124,7 +124,7 @@ impl<'a> TankSensor<'a> {
water_temp water_temp
} }
fn single_temperature_c(&mut self) -> anyhow::Result<f32> { async fn single_temperature_c(&mut self) -> anyhow::Result<f32> {
self.one_wire_bus self.one_wire_bus
.reset(&mut self.delay) .reset(&mut self.delay)
.map_err(|err| -> anyhow::Error { anyhow!("Missing attribute: {:?}", err) })?; .map_err(|err| -> anyhow::Error { anyhow!("Missing attribute: {:?}", err) })?;
@ -152,7 +152,7 @@ impl<'a> TankSensor<'a> {
anyhow::Ok(sensor_data.temperature / 10_f32) anyhow::Ok(sensor_data.temperature / 10_f32)
} }
pub fn tank_sensor_voltage(&mut self) -> anyhow::Result<f32> { pub async fn tank_sensor_voltage(&mut self) -> anyhow::Result<f32> {
self.tank_power.set_high()?; self.tank_power.set_high()?;
//let stabilize //let stabilize
self.delay.delay_ms(100); self.delay.delay_ms(100);

View File

@ -1,4 +1,5 @@
#![allow(dead_code)] #![allow(dead_code)]
#![no_std]
extern crate embedded_hal as hal; extern crate embedded_hal as hal;
pub mod sipo; pub mod sipo;

View File

@ -1,3 +1,5 @@
use alloc::string::ToString;
use alloc::vec::Vec;
use serde::Serialize; use serde::Serialize;
use std::{collections::HashMap, sync::Mutex}; use std::{collections::HashMap, sync::Mutex};
use strum::EnumIter; use strum::EnumIter;
@ -92,7 +94,7 @@ pub fn log(message_key: LogMessage, number_a: u32, number_b: u32, txt_short: &st
let template = Template::from(template_string); let template = Template::from(template_string);
let serial_entry = template.fill_in(&values); let serial_entry = template.fill_in(&values);
println!("{serial_entry}"); log::info!("{serial_entry}");
//TODO push to mqtt? //TODO push to mqtt?
let entry = LogEntry { let entry = LogEntry {

View File

@ -1,38 +1,51 @@
#![no_std]
#![no_main]
#![deny(
clippy::mem_forget,
reason = "mem::forget is generally not safe to do with esp_hal types, especially those \
holding buffers for the duration of a data transfer."
)]
use crate::config::PlantConfig; use crate::config::PlantConfig;
use crate::{ use crate::{
config::BoardVersion::INITIAL, config::BoardVersion::INITIAL,
hal::{PlantHal, HAL, PLANT_COUNT}, hal::{PlantHal, HAL, PLANT_COUNT},
webserver::httpd, //webserver::httpd,
}; };
use ::log::{error, info, warn};
use alloc::borrow::ToOwned;
use alloc::string::{String, ToString};
use alloc::sync::Arc;
use alloc::{format, vec};
use anyhow::{bail, Context}; use anyhow::{bail, Context};
use chrono::{DateTime, Datelike, Timelike, Utc}; use chrono::{DateTime, Datelike, Timelike, Utc};
use chrono_tz::Tz::{self, UTC}; use chrono_tz::Tz::{self, UTC};
use esp_idf_hal::delay::Delay; use core::sync::atomic::Ordering;
use esp_idf_sys::{ use embassy_executor::Spawner;
esp_ota_get_app_partition_count, esp_ota_get_running_partition, esp_ota_get_state_partition, use embassy_sync::blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex};
esp_ota_img_states_t, esp_ota_img_states_t_ESP_OTA_IMG_ABORTED, use embassy_sync::lazy_lock::LazyLock;
esp_ota_img_states_t_ESP_OTA_IMG_INVALID, esp_ota_img_states_t_ESP_OTA_IMG_NEW, use embassy_sync::mutex::Mutex;
esp_ota_img_states_t_ESP_OTA_IMG_PENDING_VERIFY, esp_ota_img_states_t_ESP_OTA_IMG_UNDEFINED, use embassy_sync::mutex::MutexGuard;
esp_ota_img_states_t_ESP_OTA_IMG_VALID, use embassy_time::Timer;
}; use esp_hal::{clock::CpuClock, delay::Delay, timer::systimer::SystemTimer};
use esp_ota::{mark_app_valid, rollback_and_reboot}; use esp_println::logger;
use hal::battery::BatteryState; use hal::battery::BatteryState;
use log::{log, LogMessage}; use log::{log, LogMessage};
use once_cell::sync::Lazy;
use plant_state::PlantState; use plant_state::PlantState;
use portable_atomic::AtomicBool;
use serde::{Deserialize, Serialize}; use serde::{Deserialize, Serialize};
use std::sync::{atomic::AtomicBool, Arc, Mutex, MutexGuard};
use tank::*; use tank::*;
mod config; mod config;
mod hal; mod hal;
mod log; mod log;
mod plant_state; mod plant_state;
mod tank; mod tank;
mod webserver;
pub static BOARD_ACCESS: Lazy<Mutex<HAL>> = Lazy::new(|| PlantHal::create().unwrap()); extern crate alloc;
pub static STAY_ALIVE: Lazy<AtomicBool> = Lazy::new(|| AtomicBool::new(false)); //mod webserver;
pub static BOARD_ACCESS: LazyLock<Mutex<CriticalSectionRawMutex, HAL>> =
LazyLock::new(|| PlantHal::create().unwrap());
pub static STAY_ALIVE: AtomicBool = AtomicBool::new(false);
#[derive(Serialize, Deserialize, Debug, PartialEq)] #[derive(Serialize, Deserialize, Debug, PartialEq)]
enum WaitType { enum WaitType {
@ -48,11 +61,11 @@ struct Solar {
} }
impl WaitType { impl WaitType {
fn blink_pattern(&self) -> u32 { fn blink_pattern(&self) -> u64 {
match self { match self {
WaitType::MissingConfig => 500_u32, WaitType::MissingConfig => 500_u64,
WaitType::ConfigButton => 100_u32, WaitType::ConfigButton => 100_u64,
WaitType::MqttConfig => 200_u32, WaitType::MqttConfig => 200_u64,
} }
} }
} }
@ -109,68 +122,58 @@ enum NetworkMode {
OFFLINE, OFFLINE,
} }
fn safe_main() -> anyhow::Result<()> { async fn safe_main() -> anyhow::Result<()> {
// It is necessary to call this function once. Otherwise, some patches to the runtime info!("Startup Rust");
// implemented by esp-idf-sys might not link properly. See https://github.com/esp-rs/esp-idf-template/issues/71
esp_idf_svc::sys::link_patches();
// Bind the log crate to the ESP Logging facilities
esp_idf_svc::log::EspLogger::initialize_default();
if esp_idf_sys::CONFIG_MAIN_TASK_STACK_SIZE < 25000 {
bail!(
"stack too small: {} bail!",
esp_idf_sys::CONFIG_MAIN_TASK_STACK_SIZE
)
}
println!("Startup Rust");
let mut to_config = false; let mut to_config = false;
let version = get_version(); let version = get_version();
println!( info!(
"Version using git has {} build on {}", "Version using git has {} build on {}",
version.git_hash, version.build_time version.git_hash, version.build_time
); );
let count = unsafe { esp_ota_get_app_partition_count() }; //TODO
println!("Partition count is {}", count); //let count = unsafe { esp_ota_get_app_partition_count() };
let mut ota_state: esp_ota_img_states_t = 0; //log::info!("Partition count is {}", count);
let running_partition = unsafe { esp_ota_get_running_partition() }; //let mut ota_state: esp_ota_img_states_t = 0;
let address = unsafe { (*running_partition).address }; //let running_partition = unsafe { esp_ota_get_running_partition() };
println!("Partition address is {}", address); //let partition_address = unsafe { (*running_partition).address };
//log::info!("Partition address is {}", address);
let partition_address = 0x1337;
let ota_state_string = unsafe { // TODO
esp_ota_get_state_partition(running_partition, &mut ota_state); //let ota_state_string = unsafe {
if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_NEW { //esp_ota_get_state_partition(running_partition, &mut ota_state);
"ESP_OTA_IMG_NEW" //if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_NEW {
} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_PENDING_VERIFY { //"ESP_OTA_IMG_NEW"
"ESP_OTA_IMG_PENDING_VERIFY" //} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_PENDING_VERIFY {
} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_VALID { //"ESP_OTA_IMG_PENDING_VERIFY"
"ESP_OTA_IMG_VALID" //} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_VALID {
} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_INVALID { //"ESP_OTA_IMG_VALID"
"ESP_OTA_IMG_INVALID" //} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_INVALID {
} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_ABORTED { //"ESP_OTA_IMG_INVALID"
"ESP_OTA_IMG_ABORTED" //} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_ABORTED {
} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_UNDEFINED { //"ESP_OTA_IMG_ABORTED"
"ESP_OTA_IMG_UNDEFINED" //} else if ota_state == esp_ota_img_states_t_ESP_OTA_IMG_UNDEFINED {
} else { //"ESP_OTA_IMG_UNDEFINED"
&format!("unknown {ota_state}") //} else {
} //&format!("unknown {ota_state}")
}; //}
log(LogMessage::PartitionState, 0, 0, "", ota_state_string); //};
//log(LogMessage::PartitionState, 0, 0, "", ota_state_string);
let ota_state_string = "unknown";
let mut board = BOARD_ACCESS let mut board = BOARD_ACCESS.get().lock().await;
.lock() board.board_hal.general_fault(false).await;
.expect("Could not lock board no other lock should be able to exist during startup!");
board.board_hal.general_fault(false);
let cur = board let cur = board
.board_hal .board_hal
.get_rtc_module() .get_rtc_module()
.get_rtc_time() .get_rtc_time()
.await
.or_else(|err| { .or_else(|err| {
println!("rtc module error: {:?}", err); info!("rtc module error: {:?}", err);
board.board_hal.general_fault(true); board.board_hal.general_fault(true);
board.board_hal.get_esp().time() board.board_hal.get_esp().time()
}) })
@ -185,35 +188,35 @@ fn safe_main() -> anyhow::Result<()> {
log(LogMessage::YearInplausibleForceConfig, 0, 0, "", ""); log(LogMessage::YearInplausibleForceConfig, 0, 0, "", "");
} }
println!("cur is {}", cur); info!("cur is {}", cur);
update_charge_indicator(&mut board); update_charge_indicator().await;
if board.board_hal.get_esp().get_restart_to_conf() { if board.board_hal.get_esp().get_restart_to_conf() {
log(LogMessage::ConfigModeSoftwareOverride, 0, 0, "", ""); log(LogMessage::ConfigModeSoftwareOverride, 0, 0, "", "");
for _i in 0..2 { for _i in 0..2 {
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
Delay::new_default().delay_ms(100); Timer::after_millis(100).await;
board.board_hal.general_fault(false); board.board_hal.general_fault(false).await;
Delay::new_default().delay_ms(100); Timer::after_millis(100).await;
} }
to_config = true; to_config = true;
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
board.board_hal.get_esp().set_restart_to_conf(false); board.board_hal.get_esp().set_restart_to_conf(false);
} else if board.board_hal.get_esp().mode_override_pressed() { } else if board.board_hal.get_esp().mode_override_pressed() {
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
log(LogMessage::ConfigModeButtonOverride, 0, 0, "", ""); log(LogMessage::ConfigModeButtonOverride, 0, 0, "", "");
for _i in 0..5 { for _i in 0..5 {
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
Delay::new_default().delay_ms(100); Timer::after_millis(100).await;
board.board_hal.general_fault(false); board.board_hal.general_fault(false).await;
Delay::new_default().delay_ms(100); Timer::after_millis(100).await;
} }
if board.board_hal.get_esp().mode_override_pressed() { if board.board_hal.get_esp().mode_override_pressed() {
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
to_config = true; to_config = true;
} else { } else {
board.board_hal.general_fault(false); board.board_hal.general_fault(false).await;
} }
} }
@ -223,40 +226,41 @@ fn safe_main() -> anyhow::Result<()> {
let _ = board.board_hal.get_esp().wifi_ap(); let _ = board.board_hal.get_esp().wifi_ap();
drop(board); drop(board);
let reboot_now = Arc::new(AtomicBool::new(false)); let reboot_now = Arc::new(AtomicBool::new(false));
let _webserver = httpd(reboot_now.clone()); //TODO
wait_infinity(WaitType::MissingConfig, reboot_now.clone()); //let _webserver = httpd(reboot_now.clone());
wait_infinity(WaitType::MissingConfig, reboot_now.clone()).await;
} }
println!("attempting to connect wifi"); info!("attempting to connect wifi");
let network_mode = if board.board_hal.get_config().network.ssid.is_some() { let network_mode = if board.board_hal.get_config().network.ssid.is_some() {
try_connect_wifi_sntp_mqtt(&mut board) try_connect_wifi_sntp_mqtt().await
} else { } else {
println!("No wifi configured"); info!("No wifi configured");
//the current sensors require this amount to stabilize, in case of wifi this is already handles for sure; //the current sensors require this amount to stabilize, in case of wifi this is already handles for sure;
board.board_hal.get_esp().delay.delay_ms(100); Timer::after_millis(100).await;
NetworkMode::OFFLINE NetworkMode::OFFLINE
}; };
if matches!(network_mode, NetworkMode::OFFLINE) && to_config { if matches!(network_mode, NetworkMode::OFFLINE) && to_config {
println!("Could not connect to station and config mode forced, switching to ap mode!"); info!("Could not connect to station and config mode forced, switching to ap mode!");
match board.board_hal.get_esp().wifi_ap() { match board.board_hal.get_esp().wifi_ap().await {
Ok(_) => { Ok(_) => {
println!("Started ap, continuing") info!("Started ap, continuing")
} }
Err(err) => println!("Could not start config override ap mode due to {}", err), Err(err) => info!("Could not start config override ap mode due to {}", err),
} }
} }
let timezone = match &board.board_hal.get_config().timezone { let timezone = match &board.board_hal.get_config().timezone {
Some(tz_str) => tz_str.parse::<Tz>().unwrap_or_else(|_| { Some(tz_str) => tz_str.parse::<Tz>().unwrap_or_else(|_| {
println!("Invalid timezone '{}', falling back to UTC", tz_str); info!("Invalid timezone '{}', falling back to UTC", tz_str);
UTC UTC
}), }),
None => UTC, // Fallback to UTC if no timezone is set None => UTC, // Fallback to UTC if no timezone is set
}; };
let timezone_time = cur.with_timezone(&timezone); let timezone_time = cur.with_timezone(&timezone);
println!( info!(
"Running logic at utc {} and {} {}", "Running logic at utc {} and {} {}",
cur, cur,
timezone.name(), timezone.name(),
@ -266,14 +270,14 @@ fn safe_main() -> anyhow::Result<()> {
if let NetworkMode::WIFI { ref ip_address, .. } = network_mode { if let NetworkMode::WIFI { ref ip_address, .. } = network_mode {
publish_firmware_info( publish_firmware_info(
version, version,
address, partition_address,
ota_state_string, ota_state_string,
&mut board,
ip_address, ip_address,
timezone_time, timezone_time,
); )
publish_battery_state(&mut board); .await;
let _ = publish_mppt_state(&mut board); publish_battery_state().await;
let _ = publish_mppt_state().await;
} }
log( log(
@ -292,14 +296,16 @@ fn safe_main() -> anyhow::Result<()> {
"", "",
); );
drop(board);
if to_config { if to_config {
//check if client or ap mode and init Wi-Fi //check if client or ap mode and init Wi-Fi
println!("executing config mode override"); info!("executing config mode override");
//config upload will trigger reboot! //config upload will trigger reboot!
drop(board);
let reboot_now = Arc::new(AtomicBool::new(false)); let reboot_now = Arc::new(AtomicBool::new(false));
let _webserver = httpd(reboot_now.clone()); //TODO
wait_infinity(WaitType::ConfigButton, reboot_now.clone()); //let _webserver = httpd(reboot_now.clone());
wait_infinity(WaitType::ConfigButton, reboot_now.clone()).await;
} else { } else {
log(LogMessage::NormalRun, 0, 0, "", ""); log(LogMessage::NormalRun, 0, 0, "", "");
} }
@ -346,7 +352,7 @@ fn safe_main() -> anyhow::Result<()> {
.board_hal .board_hal
.get_tank_sensor() .get_tank_sensor()
.context("no sensor") .context("no sensor")
.and_then(|f| f.water_temperature_c()); .and_then(async |f| f.water_temperature_c().await);
if let Ok(res) = water_temp { if let Ok(res) = water_temp {
if res < WATER_FROZEN_THRESH { if res < WATER_FROZEN_THRESH {
@ -354,11 +360,11 @@ fn safe_main() -> anyhow::Result<()> {
} }
} }
publish_tank_state(&mut board, &tank_state, &water_temp); publish_tank_state(&tank_state, &water_temp);
let plantstate: [PlantState; PLANT_COUNT] = let plantstate: [PlantState; PLANT_COUNT] =
core::array::from_fn(|i| PlantState::read_hardware_state(i, &mut board)); core::array::from_fn(|i| PlantState::read_hardware_state(i, &mut board).await);
publish_plant_states(&mut board, &timezone_time, &plantstate); publish_plant_states(&timezone_time, &plantstate).await;
let pump_required = plantstate let pump_required = plantstate
.iter() .iter()
@ -388,7 +394,7 @@ fn safe_main() -> anyhow::Result<()> {
&(plant_id + 1).to_string(), &(plant_id + 1).to_string(),
"", "",
); );
board.board_hal.fault(plant_id, true)?; board.board_hal.fault(plant_id, true).await?;
} }
log( log(
LogMessage::PumpPlant, LogMessage::PumpPlant,
@ -404,12 +410,11 @@ fn safe_main() -> anyhow::Result<()> {
board.board_hal.get_esp().last_pump_time(plant_id); board.board_hal.get_esp().last_pump_time(plant_id);
//state.active = true; //state.active = true;
pump_info(&mut board, plant_id, true, pump_ineffective, 0, 0, 0, false); pump_info(plant_id, true, pump_ineffective, 0, 0, 0, false).await;
let result = do_secure_pump(&mut board, plant_id, plant_config, dry_run)?; let result = do_secure_pump(plant_id, plant_config, dry_run).await?;
board.board_hal.pump(plant_id, false)?; board.board_hal.pump(plant_id, false).await?;
pump_info( pump_info(
&mut board,
plant_id, plant_id,
false, false,
pump_ineffective, pump_ineffective,
@ -417,7 +422,8 @@ fn safe_main() -> anyhow::Result<()> {
result.max_current_ma, result.max_current_ma,
result.min_current_ma, result.min_current_ma,
result.error, result.error,
); )
.await;
} else if !state.pump_in_timeout(plant_config, &timezone_time) { } else if !state.pump_in_timeout(plant_config, &timezone_time) {
// plant does not need to be watered and is not in timeout // plant does not need to be watered and is not in timeout
// -> reset consecutive pump count // -> reset consecutive pump count
@ -434,6 +440,7 @@ fn safe_main() -> anyhow::Result<()> {
.board_hal .board_hal
.get_battery_monitor() .get_battery_monitor()
.state_charge_percent() .state_charge_percent()
.await
.unwrap_or(0.); .unwrap_or(0.);
// try to load full battery state if failed the battery state is unknown // try to load full battery state if failed the battery state is unknown
@ -441,6 +448,7 @@ fn safe_main() -> anyhow::Result<()> {
.board_hal .board_hal
.get_battery_monitor() .get_battery_monitor()
.get_battery_state() .get_battery_state()
.await
.unwrap_or(BatteryState::Unknown); .unwrap_or(BatteryState::Unknown);
let mut light_state = LightState { let mut light_state = LightState {
@ -506,7 +514,7 @@ fn safe_main() -> anyhow::Result<()> {
board.board_hal.light(false)?; board.board_hal.light(false)?;
} }
println!("Lightstate is {:?}", light_state); info!("Lightstate is {:?}", light_state);
} }
match serde_json::to_string(&light_state) { match serde_json::to_string(&light_state) {
@ -514,10 +522,11 @@ fn safe_main() -> anyhow::Result<()> {
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/light", state.as_bytes()); .mqtt_publish("/light", state.as_bytes())
.await;
} }
Err(err) => { Err(err) => {
println!("Error publishing lightstate {}", err); info!("Error publishing lightstate {}", err);
} }
}; };
@ -527,52 +536,55 @@ fn safe_main() -> anyhow::Result<()> {
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/deepsleep", "low Volt 12h".as_bytes()); .mqtt_publish("/deepsleep", "low Volt 12h".as_bytes()).await;
12 * 60 12 * 60
} else if is_day { } else if is_day {
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/deepsleep", "normal 20m".as_bytes()); .mqtt_publish("/deepsleep", "normal 20m".as_bytes()).await;
20 20
} else { } else {
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/deepsleep", "night 1h".as_bytes()); .mqtt_publish("/deepsleep", "night 1h".as_bytes()).await;
60 60
}; };
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/state", "sleep".as_bytes()); .mqtt_publish("/state", "sleep".as_bytes())
.await;
//determine next event //determine next event
//is light out of work trigger soon? //is light out of work trigger soon?
//is battery low ?? //is battery low ??
//is deep sleep //is deep sleep
mark_app_valid(); //TODO
//mark_app_valid();
let stay_alive_mqtt = STAY_ALIVE.load(std::sync::atomic::Ordering::Relaxed); let stay_alive_mqtt = STAY_ALIVE.load(Ordering::Relaxed);
let stay_alive = stay_alive_mqtt; let stay_alive = stay_alive_mqtt;
println!("Check stay alive, current state is {}", stay_alive); info!("Check stay alive, current state is {}", stay_alive);
if stay_alive { if stay_alive {
println!("Go to stay alive move"); info!("Go to stay alive move");
drop(board); drop(board);
let reboot_now = Arc::new(AtomicBool::new(false)); let reboot_now = Arc::new(AtomicBool::new(false));
let _webserver = httpd(reboot_now.clone()); //TODO
wait_infinity(WaitType::MqttConfig, reboot_now.clone()); //let _webserver = httpd(reboot_now.clone());
wait_infinity(WaitType::MqttConfig, reboot_now.clone()).await;
} else {
board.board_hal.get_esp().set_restart_to_conf(false);
board
.board_hal
.deep_sleep(1000 * 1000 * 60 * deep_sleep_duration_minutes as u64);
} }
board.board_hal.get_esp().set_restart_to_conf(false);
board
.board_hal
.deep_sleep(1000 * 1000 * 60 * deep_sleep_duration_minutes as u64);
} }
pub fn do_secure_pump( pub async fn do_secure_pump(
board: &mut MutexGuard<HAL>,
plant_id: usize, plant_id: usize,
plant_config: &PlantConfig, plant_config: &PlantConfig,
dry_run: bool, dry_run: bool,
@ -582,6 +594,7 @@ pub fn do_secure_pump(
let mut error = false; let mut error = false;
let mut first_error = true; let mut first_error = true;
let mut pump_time_s = 0; let mut pump_time_s = 0;
let board = &mut BOARD_ACCESS.get().lock().await;
if !dry_run { if !dry_run {
board board
.board_hal .board_hal
@ -593,8 +606,8 @@ pub fn do_secure_pump(
.get_tank_sensor() .get_tank_sensor()
.unwrap() .unwrap()
.start_flow_meter(); .start_flow_meter();
board.board_hal.pump(plant_id, true)?; board.board_hal.pump(plant_id, true).await?;
Delay::new_default().delay_ms(10); Timer::after_millis(10).await;
for step in 0..plant_config.pump_time_s as usize { for step in 0..plant_config.pump_time_s as usize {
let flow_value = board let flow_value = board
.board_hal .board_hal
@ -604,16 +617,16 @@ pub fn do_secure_pump(
flow_collector[step] = flow_value; flow_collector[step] = flow_value;
let flow_value_ml = flow_value as f32 * board.board_hal.get_config().tank.ml_per_pulse; let flow_value_ml = flow_value as f32 * board.board_hal.get_config().tank.ml_per_pulse;
println!( info!(
"Flow value is {} ml, limit is {} ml raw sensor {}", "Flow value is {} ml, limit is {} ml raw sensor {}",
flow_value_ml, plant_config.pump_limit_ml, flow_value flow_value_ml, plant_config.pump_limit_ml, flow_value
); );
if flow_value_ml > plant_config.pump_limit_ml as f32 { if flow_value_ml > plant_config.pump_limit_ml as f32 {
println!("Flow value is reached, stopping"); info!("Flow value is reached, stopping");
break; break;
} }
let current = board.board_hal.pump_current(plant_id); let current = board.board_hal.pump_current(plant_id).await;
match current { match current {
Ok(current) => { Ok(current) => {
let current_ma = current.as_milliamperes() as u16; let current_ma = current.as_milliamperes() as u16;
@ -628,8 +641,8 @@ pub fn do_secure_pump(
plant_config.max_pump_current_ma.to_string().as_str(), plant_config.max_pump_current_ma.to_string().as_str(),
step.to_string().as_str(), step.to_string().as_str(),
); );
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
board.board_hal.fault(plant_id, true)?; board.board_hal.fault(plant_id, true).await?;
if !plant_config.ignore_current_error { if !plant_config.ignore_current_error {
error = true; error = true;
break; break;
@ -647,8 +660,8 @@ pub fn do_secure_pump(
plant_config.min_pump_current_ma.to_string().as_str(), plant_config.min_pump_current_ma.to_string().as_str(),
step.to_string().as_str(), step.to_string().as_str(),
); );
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
board.board_hal.fault(plant_id, true)?; board.board_hal.fault(plant_id, true).await?;
if !plant_config.ignore_current_error { if !plant_config.ignore_current_error {
error = true; error = true;
break; break;
@ -659,7 +672,7 @@ pub fn do_secure_pump(
} }
Err(err) => { Err(err) => {
if !plant_config.ignore_current_error { if !plant_config.ignore_current_error {
println!("Error getting pump current: {}", err); info!("Error getting pump current: {}", err);
log( log(
LogMessage::PumpMissingSensorCurrent, LogMessage::PumpMissingSensorCurrent,
plant_id as u32, plant_id as u32,
@ -674,7 +687,7 @@ pub fn do_secure_pump(
} }
} }
} }
Delay::new_default().delay_ms(1000); Timer::after_millis(1000).await;
pump_time_s += 1; pump_time_s += 1;
} }
} }
@ -685,7 +698,7 @@ pub fn do_secure_pump(
.unwrap() .unwrap()
.get_flow_meter_value(); .get_flow_meter_value();
let flow_value_ml = final_flow_value as f32 * board.board_hal.get_config().tank.ml_per_pulse; let flow_value_ml = final_flow_value as f32 * board.board_hal.get_config().tank.ml_per_pulse;
println!( info!(
"Final flow value is {} with {} ml", "Final flow value is {} with {} ml",
final_flow_value, flow_value_ml final_flow_value, flow_value_ml
); );
@ -701,9 +714,10 @@ pub fn do_secure_pump(
}) })
} }
fn update_charge_indicator(board: &mut MutexGuard<HAL>) { async fn update_charge_indicator() {
let board = BOARD_ACCESS.get().lock().await;
//we have mppt controller, ask it for charging current //we have mppt controller, ask it for charging current
if let Ok(current) = board.board_hal.get_mptt_current() { if let Ok(current) = board.board_hal.get_mptt_current().await {
let _ = board let _ = board
.board_hal .board_hal
.set_charge_indicator(current.as_milliamperes() > 20_f64); .set_charge_indicator(current.as_milliamperes() > 20_f64);
@ -721,11 +735,8 @@ fn update_charge_indicator(board: &mut MutexGuard<HAL>) {
} }
} }
fn publish_tank_state( async fn publish_tank_state(tank_state: &TankState, water_temp: &anyhow::Result<f32>) {
board: &mut MutexGuard<HAL>, let board = &mut BOARD_ACCESS.get().lock().await;
tank_state: &TankState,
water_temp: &anyhow::Result<f32>,
) {
match serde_json::to_string( match serde_json::to_string(
&tank_state.as_mqtt_info(&board.board_hal.get_config().tank, water_temp), &tank_state.as_mqtt_info(&board.board_hal.get_config().tank, water_temp),
) { ) {
@ -736,16 +747,13 @@ fn publish_tank_state(
.mqtt_publish("/water", state.as_bytes()); .mqtt_publish("/water", state.as_bytes());
} }
Err(err) => { Err(err) => {
println!("Error publishing tankstate {}", err); info!("Error publishing tankstate {}", err);
} }
}; };
} }
fn publish_plant_states( async fn publish_plant_states(timezone_time: &DateTime<Tz>, plantstate: &[PlantState; 8]) {
board: &mut MutexGuard<HAL>, let board = &mut BOARD_ACCESS.get().lock().await;
timezone_time: &DateTime<Tz>,
plantstate: &[PlantState; 8],
) {
for (plant_id, (plant_state, plant_conf)) in plantstate for (plant_id, (plant_state, plant_conf)) in plantstate
.iter() .iter()
.zip(&board.board_hal.get_config().plants.clone()) .zip(&board.board_hal.get_config().plants.clone())
@ -757,37 +765,41 @@ fn publish_plant_states(
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish(&plant_topic, state.as_bytes()); .mqtt_publish(&plant_topic, state.as_bytes())
//reduce speed as else messages will be dropped .await;
board.board_hal.get_esp().delay.delay_ms(200); //TODO? reduce speed as else messages will be dropped
Timer::after_millis(200).await
} }
Err(err) => { Err(err) => {
println!("Error publishing plant state {}", err); error!("Error publishing plant state {}", err);
} }
}; };
} }
} }
fn publish_firmware_info( async fn publish_firmware_info(
version: VersionInfo, version: VersionInfo,
address: u32, address: u32,
ota_state_string: &str, ota_state_string: &str,
board: &mut MutexGuard<HAL>,
ip_address: &String, ip_address: &String,
timezone_time: DateTime<Tz>, timezone_time: DateTime<Tz>,
) { ) {
let board = &mut BOARD_ACCESS.get().lock().await;
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/firmware/address", ip_address.as_bytes()); .mqtt_publish("/firmware/address", ip_address.as_bytes())
.await;
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/firmware/githash", version.git_hash.as_bytes()); .mqtt_publish("/firmware/githash", version.git_hash.as_bytes())
.await;
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/firmware/buildtime", version.build_time.as_bytes()); .mqtt_publish("/firmware/buildtime", version.build_time.as_bytes())
.await;
let _ = board.board_hal.get_esp().mqtt_publish( let _ = board.board_hal.get_esp().mqtt_publish(
"/firmware/last_online", "/firmware/last_online",
timezone_time.to_rfc3339().as_bytes(), timezone_time.to_rfc3339().as_bytes(),
@ -795,7 +807,8 @@ fn publish_firmware_info(
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/firmware/ota_state", ota_state_string.as_bytes()); .mqtt_publish("/firmware/ota_state", ota_state_string.as_bytes())
.await;
let _ = board.board_hal.get_esp().mqtt_publish( let _ = board.board_hal.get_esp().mqtt_publish(
"/firmware/partition_address", "/firmware/partition_address",
format!("{:#06x}", address).as_bytes(), format!("{:#06x}", address).as_bytes(),
@ -803,34 +816,36 @@ fn publish_firmware_info(
let _ = board let _ = board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/state", "online".as_bytes()); .mqtt_publish("/state", "online".as_bytes())
.await;
} }
fn try_connect_wifi_sntp_mqtt(board: &mut MutexGuard<HAL>) -> NetworkMode { async fn try_connect_wifi_sntp_mqtt() -> NetworkMode {
let board = BOARD_ACCESS.get().lock().await;
let nw_conf = &board.board_hal.get_config().network.clone(); let nw_conf = &board.board_hal.get_config().network.clone();
match board.board_hal.get_esp().wifi(nw_conf) { match board.board_hal.get_esp().wifi(nw_conf).await {
Ok(ip_info) => { Ok(ip_info) => {
let sntp_mode: SntpMode = match board.board_hal.get_esp().sntp(1000 * 10) { let sntp_mode: SntpMode = match board.board_hal.get_esp().sntp(1000 * 10).await {
Ok(new_time) => { Ok(new_time) => {
println!("Using time from sntp"); info!("Using time from sntp");
let _ = board.board_hal.get_rtc_module().set_rtc_time(&new_time); let _ = board.board_hal.get_rtc_module().set_rtc_time(&new_time);
SntpMode::SYNC { current: new_time } SntpMode::SYNC { current: new_time }
} }
Err(err) => { Err(err) => {
println!("sntp error: {}", err); warn!("sntp error: {}", err);
board.board_hal.general_fault(true); board.board_hal.general_fault(true).await;
SntpMode::OFFLINE SntpMode::OFFLINE
} }
}; };
let mqtt_connected = if board.board_hal.get_config().network.mqtt_url.is_some() { 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 = &board.board_hal.get_config().network.clone();
match board.board_hal.get_esp().mqtt(nw_config) { match board.board_hal.get_esp().mqtt(nw_config).await {
Ok(_) => { Ok(_) => {
println!("Mqtt connection ready"); info!("Mqtt connection ready");
true true
} }
Err(err) => { Err(err) => {
println!("Could not connect mqtt due to {}", err); warn!("Could not connect mqtt due to {}", err);
false false
} }
} }
@ -844,15 +859,14 @@ fn try_connect_wifi_sntp_mqtt(board: &mut MutexGuard<HAL>) -> NetworkMode {
} }
} }
Err(_) => { Err(_) => {
println!("Offline mode"); info!("Offline mode");
board.board_hal.general_fault(true); board.board_hal.general_fault(true);
NetworkMode::OFFLINE NetworkMode::OFFLINE
} }
} }
} }
fn pump_info( async fn pump_info(
board: &mut MutexGuard<HAL>,
plant_id: usize, plant_id: usize,
pump_active: bool, pump_active: bool,
pump_ineffective: bool, pump_ineffective: bool,
@ -869,24 +883,30 @@ fn pump_info(
min_current_ma: min_current_ma, min_current_ma: min_current_ma,
}; };
let pump_topic = format!("/pump{}", plant_id + 1); let pump_topic = format!("/pump{}", plant_id + 1);
match serde_json::to_string(&pump_info) { match serde_json::to_string(&pump_info) {
Ok(state) => { Ok(state) => {
let _ = board let _ = BOARD_ACCESS
.get()
.lock()
.await
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish(&pump_topic, state.as_bytes()); .mqtt_publish(&pump_topic, state.as_bytes());
//reduce speed as else messages will be dropped //reduce speed as else messages will be dropped
Delay::new_default().delay_ms(200); //TODO maybee not required for low level hal?
Timer::after_millis(200).await;
} }
Err(err) => { Err(err) => {
println!("Error publishing pump state {}", err); warn!("Error publishing pump state {}", err);
} }
}; };
} }
fn publish_mppt_state(board: &mut MutexGuard<'_, HAL<'_>>) -> anyhow::Result<()> { async fn publish_mppt_state() -> anyhow::Result<()> {
let current = board.board_hal.get_mptt_current()?; let board_hal = &mut BOARD_ACCESS.get().lock().await.board_hal;
let voltage = board.board_hal.get_mptt_voltage()?; let current = board_hal.get_mptt_current().await?;
let voltage = board_hal.get_mptt_voltage().await?;
let solar_state = Solar { let solar_state = Solar {
current_ma: current.as_milliamperes() as u32, current_ma: current.as_milliamperes() as u32,
voltage_ma: voltage.as_millivolts() as u32, voltage_ma: voltage.as_millivolts() as u32,
@ -894,35 +914,33 @@ fn publish_mppt_state(board: &mut MutexGuard<'_, HAL<'_>>) -> anyhow::Result<()>
if let Ok(serialized_solar_state_bytes) = if let Ok(serialized_solar_state_bytes) =
serde_json::to_string(&solar_state).map(|s| s.into_bytes()) serde_json::to_string(&solar_state).map(|s| s.into_bytes())
{ {
let _ = board let _ = board_hal
.board_hal
.get_esp() .get_esp()
.mqtt_publish("/mppt", &serialized_solar_state_bytes); .mqtt_publish("/mppt", &serialized_solar_state_bytes);
} }
Ok(()) Ok(())
} }
fn publish_battery_state(board: &mut MutexGuard<'_, HAL<'_>>) { async fn publish_battery_state() -> () {
let board = BOARD_ACCESS.get().lock().await;
let state = board.board_hal.get_battery_monitor().get_battery_state(); let state = board.board_hal.get_battery_monitor().get_battery_state();
if let Ok(serialized_battery_state_bytes) = if let Ok(serialized_battery_state_bytes) =
serde_json::to_string(&state).map(|s| s.into_bytes()) serde_json::to_string(&state).map(|s| s.into_bytes())
{ {
let _ = board board
.board_hal .board_hal
.get_esp() .get_esp()
.mqtt_publish("/battery", &serialized_battery_state_bytes); .mqtt_publish("/battery", &serialized_battery_state_bytes);
} }
} }
fn wait_infinity(wait_type: WaitType, reboot_now: Arc<AtomicBool>) -> ! { async fn wait_infinity(wait_type: WaitType, reboot_now: Arc<AtomicBool>) -> ! {
let delay = wait_type.blink_pattern(); let delay = wait_type.blink_pattern();
let mut led_count = 8; let mut led_count = 8;
let mut pattern_step = 0; let mut pattern_step = 0;
let delay_handle = Delay::new_default();
loop { loop {
let mut board = BOARD_ACCESS.lock().unwrap(); update_charge_indicator().await;
update_charge_indicator(&mut board); let mut board = BOARD_ACCESS.get().lock().await;
match wait_type { match wait_type {
WaitType::MissingConfig => { WaitType::MissingConfig => {
// Keep existing behavior: circular filling pattern // Keep existing behavior: circular filling pattern
@ -950,9 +968,9 @@ fn wait_infinity(wait_type: WaitType, reboot_now: Arc<AtomicBool>) -> ! {
board.board_hal.general_fault(true); board.board_hal.general_fault(true);
drop(board); drop(board);
//cannot use shared delay as that is inside the mutex here
delay_handle.delay_ms(delay); Timer::after_millis(delay).await;
let mut board = BOARD_ACCESS.lock().unwrap(); let mut board = BOARD_ACCESS.get().lock().await;
board.board_hal.general_fault(false); board.board_hal.general_fault(false);
// Clear all LEDs // Clear all LEDs
@ -960,41 +978,50 @@ fn wait_infinity(wait_type: WaitType, reboot_now: Arc<AtomicBool>) -> ! {
let _ = board.board_hal.fault(i, false); let _ = board.board_hal.fault(i, false);
} }
drop(board); drop(board);
delay_handle.delay_ms(delay); Timer::after_millis(delay).await;
if wait_type == WaitType::MqttConfig if wait_type == WaitType::MqttConfig && !STAY_ALIVE.load(Ordering::Relaxed) {
&& !STAY_ALIVE.load(std::sync::atomic::Ordering::Relaxed) reboot_now.store(true, Ordering::Relaxed);
{
reboot_now.store(true, std::sync::atomic::Ordering::Relaxed);
} }
if reboot_now.load(std::sync::atomic::Ordering::Relaxed) { if reboot_now.load(Ordering::Relaxed) {
//ensure clean http answer //ensure clean http answer
Delay::new_default().delay_ms(500); Timer::after_millis(500).await;
BOARD_ACCESS.lock().unwrap().board_hal.deep_sleep(1); BOARD_ACCESS.get().lock().await.board_hal.deep_sleep(1);
} }
} }
} }
fn main() { #[esp_hal_embassy::main]
let result = safe_main(); async fn main(spawner: Spawner) {
// intialize embassy
logger::init_logger_from_env();
let config = esp_hal::Config::default().with_cpu_clock(CpuClock::max());
let peripherals = esp_hal::init(config);
esp_alloc::heap_allocator!(size: 64 * 1024);
let timer0 = SystemTimer::new(peripherals.SYSTIMER);
esp_hal_embassy::init(timer0.alarm0);
info!("Embassy initialized!");
let result = safe_main().await;
match result { match result {
// this should not get triggered, safe_main should not return but go into deep sleep with sensible // this should not get triggered, safe_main should not return but go into deep sleep with sensible
// timeout, this is just a fallback // timeout, this is just a fallback
Ok(_) => { Ok(_) => {
println!("Main app finished, restarting"); warn!("Main app finished, but should never do, restarting");
BOARD_ACCESS let board = &mut BOARD_ACCESS.get().lock().await.board_hal;
.lock()
.unwrap() board.get_esp().set_restart_to_conf(false);
.board_hal board.deep_sleep(1);
.get_esp()
.set_restart_to_conf(false);
BOARD_ACCESS.lock().unwrap().board_hal.deep_sleep(1);
} }
// if safe_main exists with an error, rollback to a known good ota version // if safe_main exists with an error, rollback to a known good ota version
Err(err) => { Err(err) => {
println!("Failed main {}", err); error!("Failed main {}", err);
let _rollback_successful = rollback_and_reboot(); //TODO
panic!("Failed to rollback :("); //let _rollback_successful = rollback_and_reboot();
//panic!("Failed to rollback :(");
} }
} }
} }
@ -1014,8 +1041,10 @@ fn get_version() -> VersionInfo {
let branch = env!("VERGEN_GIT_BRANCH").to_owned(); let branch = env!("VERGEN_GIT_BRANCH").to_owned();
let hash = &env!("VERGEN_GIT_SHA")[0..8]; let hash = &env!("VERGEN_GIT_SHA")[0..8];
let running_partition = unsafe { esp_ota_get_running_partition() }; //TODO
let address = unsafe { (*running_partition).address }; //let running_partition = unsafe { esp_ota_get_running_partition() };
let address = 0;
//let address = unsafe { (*running_partition).address };
let partition = if address > 100000 { let partition = if address > 100000 {
"ota_1 @ " "ota_1 @ "
} else { } else {

View File

@ -3,6 +3,7 @@ use crate::{
hal::{Sensor, HAL}, hal::{Sensor, HAL},
in_time_range, in_time_range,
}; };
use alloc::string::String;
use chrono::{DateTime, TimeDelta, Utc}; use chrono::{DateTime, TimeDelta, Utc};
use chrono_tz::Tz; use chrono_tz::Tz;
use serde::{Deserialize, Serialize}; use serde::{Deserialize, Serialize};
@ -115,7 +116,7 @@ fn map_range_moisture(
} }
impl PlantState { impl PlantState {
pub fn read_hardware_state(plant_id: usize, board: &mut HAL) -> Self { 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 { 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) { match board.board_hal.measure_moisture_hz(plant_id, Sensor::A) {
Ok(raw) => match map_range_moisture( Ok(raw) => match map_range_moisture(

View File

@ -2,7 +2,9 @@
use core::cell::RefCell; use core::cell::RefCell;
use core::mem::{self, MaybeUninit}; use core::mem::{self, MaybeUninit};
use std::convert::Infallible; use core::convert::Infallible;
use core::result::{Result, Result::Ok};
use core::iter::Iterator;
use hal::digital::OutputPin; use hal::digital::OutputPin;

View File

@ -1,5 +1,6 @@
use crate::{config::TankConfig, hal::HAL}; use crate::{config::TankConfig, hal::HAL};
use anyhow::Context; use anyhow::Context;
use crate::alloc::string::{String, ToString};
use serde::Serialize; use serde::Serialize;
const OPEN_TANK_VOLTAGE: f32 = 3.0; const OPEN_TANK_VOLTAGE: f32 = 3.0;

View File

@ -187,7 +187,7 @@ fn get_backup_config(
let json = match board.board_hal.get_rtc_module().get_backup_config() { let json = match board.board_hal.get_rtc_module().get_backup_config() {
Ok(config) => from_utf8(&config)?.to_owned(), Ok(config) => from_utf8(&config)?.to_owned(),
Err(err) => { Err(err) => {
println!("Error get backup config {:?}", err); log::info!("Error get backup config {:?}", err);
err.to_string() err.to_string()
} }
}; };
@ -318,7 +318,7 @@ fn wifi_scan(
let mut ssids: Vec<&String<32>> = Vec::new(); let mut ssids: Vec<&String<32>> = Vec::new();
scan_result.iter().for_each(|s| ssids.push(&s.ssid)); scan_result.iter().for_each(|s| ssids.push(&s.ssid));
let ssid_json = serde_json::to_string(&SSIDList { ssids })?; let ssid_json = serde_json::to_string(&SSIDList { ssids })?;
println!("Sending ssid list {}", &ssid_json); log::info!("Sending ssid list {}", &ssid_json);
anyhow::Ok(Some(ssid_json)) anyhow::Ok(Some(ssid_json))
} }
@ -338,7 +338,7 @@ fn ota(
) -> Result<Option<std::string::String>, anyhow::Error> { ) -> Result<Option<std::string::String>, anyhow::Error> {
let mut board = BOARD_ACCESS.lock().unwrap(); let mut board = BOARD_ACCESS.lock().unwrap();
let mut ota = OtaUpdate::begin()?; let mut ota = OtaUpdate::begin()?;
println!("start ota"); log::info!("start ota");
//having a larger buffer is not really faster, requires more stack and prevents the progress bar from working ;) //having a larger buffer is not really faster, requires more stack and prevents the progress bar from working ;)
const BUFFER_SIZE: usize = 512; const BUFFER_SIZE: usize = 512;
@ -366,13 +366,13 @@ fn ota(
break; break;
} }
} }
println!("wrote bytes ota {total_read}"); log::info!("wrote bytes ota {total_read}");
println!("finish ota"); log::info!("finish ota");
let partition = ota.raw_partition(); let partition = ota.raw_partition();
println!("finalizing and changing boot partition to {partition:?}"); log::info!("finalizing and changing boot partition to {partition:?}");
let mut finalizer = ota.finalize()?; let mut finalizer = ota.finalize()?;
println!("changing boot partition"); log::info!("changing boot partition");
board.board_hal.get_esp().set_restart_to_conf(true); board.board_hal.get_esp().set_restart_to_conf(true);
drop(board); drop(board);
finalizer.set_as_boot_partition()?; finalizer.set_as_boot_partition()?;
@ -380,7 +380,7 @@ fn ota(
} }
fn query_param(uri: &str, param_name: &str) -> Option<std::string::String> { fn query_param(uri: &str, param_name: &str) -> Option<std::string::String> {
println!("{uri} get {param_name}"); log::info!("{uri} get {param_name}");
let parsed = Url::parse(&format!("http://127.0.0.1/{uri}")).unwrap(); let parsed = Url::parse(&format!("http://127.0.0.1/{uri}")).unwrap();
let value = parsed.query_pairs().find(|it| it.0 == param_name); let value = parsed.query_pairs().find(|it| it.0 == param_name);
match value { match value {
@ -551,14 +551,14 @@ pub fn httpd(reboot_now: Arc<AtomicBool>) -> Box<EspHttpServer<'static>> {
break; break;
} }
} }
println!("wrote {total_read} for file {filename}"); log::info!("wrote {total_read} for file {filename}");
drop(file_handle); drop(file_handle);
response.flush()?; response.flush()?;
} }
Err(err) => { Err(err) => {
//todo set headers here for filename to be error //todo set headers here for filename to be error
let error_text = err.to_string(); let error_text = err.to_string();
println!("error handling get file {}", error_text); log::info!("error handling get file {}", error_text);
cors_response(request, 500, &error_text)?; cors_response(request, 500, &error_text)?;
} }
} }
@ -599,7 +599,7 @@ pub fn httpd(reboot_now: Arc<AtomicBool>) -> Box<EspHttpServer<'static>> {
Err(err) => { Err(err) => {
//todo set headers here for filename to be error //todo set headers here for filename to be error
let error_text = err.to_string(); let error_text = err.to_string();
println!("error handling get file {}", error_text); log::info!("error handling get file {}", error_text);
cors_response(request, 500, &error_text)?; cors_response(request, 500, &error_text)?;
} }
} }
@ -697,7 +697,7 @@ fn handle_error_to500(
}, },
Err(err) => { Err(err) => {
let error_text = err.to_string(); let error_text = err.to_string();
println!("error handling process {}", error_text); log::info!("error handling process {}", error_text);
cors_response(request, 500, &error_text)?; cors_response(request, 500, &error_text)?;
} }
} }
@ -725,6 +725,6 @@ fn read_up_to_bytes_from_request(
data_store.push(actual_data.to_owned()); data_store.push(actual_data.to_owned());
} }
let allvec = data_store.concat(); let allvec = data_store.concat();
println!("Raw data {}", from_utf8(&allvec)?); log::info!("Raw data {}", from_utf8(&allvec)?);
Ok(allvec) Ok(allvec)
} }