tanksensor and rtc sync
This commit is contained in:
		| @@ -6,7 +6,6 @@ use core::str::Utf8Error; | ||||
| use embassy_embedded_hal::shared_bus::I2cDeviceError; | ||||
| use embassy_executor::SpawnError; | ||||
| use embassy_sync::mutex::TryLockError; | ||||
| use esp_bootloader_esp_idf::partitions::DataPartitionSubType::Fat; | ||||
| use esp_hal::i2c::master::ConfigError; | ||||
| use esp_wifi::wifi::WifiError; | ||||
| use ina219::errors::{BusVoltageReadError, ShuntVoltageReadError}; | ||||
|   | ||||
| @@ -1,7 +1,7 @@ | ||||
| use crate::bail; | ||||
| use crate::config::{NetworkConfig, PlantControllerConfig}; | ||||
| use crate::hal::{GW_IP_ADDR_ENV, PLANT_COUNT, TIME_ACCESS}; | ||||
| use crate::hal::PLANT_COUNT; | ||||
| use crate::log::{LogMessage, LOG_ACCESS}; | ||||
| use crate::{bail, STAY_ALIVE}; | ||||
| use chrono::{DateTime, Utc}; | ||||
| use serde::Serialize; | ||||
|  | ||||
| @@ -32,7 +32,7 @@ use esp_wifi::wifi::{ | ||||
|     ScanTypeConfig, WifiController, WifiDevice, | ||||
| }; | ||||
| use littlefs2::fs::Filesystem; | ||||
| use littlefs2_core::{DynFile, FileType, PathBuf, SeekFrom}; | ||||
| use littlefs2_core::{FileType, PathBuf, SeekFrom}; | ||||
| use log::info; | ||||
|  | ||||
| #[esp_hal::ram(rtc_fast, persistent)] | ||||
| @@ -81,7 +81,6 @@ pub struct Esp<'a> { | ||||
|     pub(crate) mqtt_client: Option<MqttClient<'a>>, | ||||
|  | ||||
|     pub boot_button: Input<'a>, | ||||
|     pub(crate) wall_clock_offset: u64, | ||||
|  | ||||
|     pub ota: Ota<'static, FlashStorage>, | ||||
|     pub ota_next: &'static mut FlashRegion<'static, FlashStorage>, | ||||
| @@ -344,7 +343,7 @@ impl Esp<'_> { | ||||
|     } | ||||
|  | ||||
|     pub async fn deep_sleep(&mut self, duration_in_ms: u64) -> ! { | ||||
|         let mut cfg = RtcSleepConfig::deep(); | ||||
|         RtcSleepConfig::deep(); | ||||
|  | ||||
|         let cur = self.ota.current_ota_state().unwrap(); | ||||
|         //we made it till here, so fine | ||||
|   | ||||
| @@ -1,8 +1,6 @@ | ||||
| use crate::alloc::boxed::Box; | ||||
| use crate::hal::esp::Esp; | ||||
| use crate::hal::rtc::{BackupHeader, RTCModuleInteraction}; | ||||
| use alloc::vec::Vec; | ||||
| //use crate::hal::water::TankSensor; | ||||
| use crate::alloc::boxed::Box; | ||||
| use crate::hal::water::TankSensor; | ||||
| use crate::hal::{BoardInteraction, FreePeripherals, Sensor}; | ||||
| use crate::FatError::{FatError, FatResult}; | ||||
| @@ -32,15 +30,15 @@ impl RTCModuleInteraction for NoRTC { | ||||
|         bail!("Please configure board revision") | ||||
|     } | ||||
|  | ||||
|     async fn get_backup_config(&mut self, chunk: usize) -> FatResult<([u8; 32], usize, u16)> { | ||||
|     async fn get_backup_config(&mut self, _chunk: usize) -> FatResult<([u8; 32], usize, u16)> { | ||||
|         bail!("Please configure board revision") | ||||
|     } | ||||
|  | ||||
|     async fn backup_config(&mut self, offset: usize, bytes: &[u8]) -> FatResult<()> { | ||||
|     async fn backup_config(&mut self, _offset: usize, _bytes: &[u8]) -> FatResult<()> { | ||||
|         bail!("Please configure board revision") | ||||
|     } | ||||
|  | ||||
|     async fn backup_config_finalize(&mut self, crc: u16, length: usize) -> FatResult<()> { | ||||
|     async fn backup_config_finalize(&mut self, _crc: u16, _length: usize) -> FatResult<()> { | ||||
|         bail!("Please configure board revision") | ||||
|     } | ||||
|  | ||||
|   | ||||
| @@ -10,6 +10,8 @@ mod water; | ||||
| use crate::alloc::string::ToString; | ||||
| use crate::hal::rtc::{DS3231Module, RTCModuleInteraction}; | ||||
| use esp_hal::peripherals::Peripherals; | ||||
| use esp_hal::peripherals::ADC1; | ||||
| use esp_hal::peripherals::APB_SARADC; | ||||
| use esp_hal::peripherals::GPIO0; | ||||
| use esp_hal::peripherals::GPIO1; | ||||
| use esp_hal::peripherals::GPIO10; | ||||
| @@ -38,6 +40,7 @@ use esp_hal::peripherals::GPIO5; | ||||
| use esp_hal::peripherals::GPIO6; | ||||
| use esp_hal::peripherals::GPIO7; | ||||
| use esp_hal::peripherals::GPIO8; | ||||
| use esp_hal::peripherals::PCNT; | ||||
| use esp_hal::peripherals::TWAI0; | ||||
|  | ||||
| use crate::{ | ||||
| @@ -48,6 +51,7 @@ use crate::{ | ||||
|         esp::Esp, | ||||
|     }, | ||||
|     log::LogMessage, | ||||
|     BOARD_ACCESS, | ||||
| }; | ||||
| use alloc::boxed::Box; | ||||
| use alloc::format; | ||||
| @@ -65,10 +69,10 @@ use eeprom24x::unique_serial::No; | ||||
| use eeprom24x::{Eeprom24x, SlaveAddr, Storage}; | ||||
| use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice; | ||||
| use embassy_executor::Spawner; | ||||
| use embassy_sync::blocking_mutex::{CriticalSectionMutex, NoopMutex}; | ||||
| use embassy_sync::blocking_mutex::CriticalSectionMutex; | ||||
| //use battery::BQ34Z100G1; | ||||
| //use bq34z100::Bq34z100g1Driver; | ||||
| use embassy_sync::blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}; | ||||
| use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; | ||||
| use esp_bootloader_esp_idf::partitions::{ | ||||
|     AppPartitionSubType, DataPartitionSubType, FlashRegion, PartitionEntry, | ||||
| }; | ||||
| @@ -86,15 +90,15 @@ use embassy_sync::once_lock::OnceLock; | ||||
| use esp_alloc as _; | ||||
| use esp_backtrace as _; | ||||
| use esp_bootloader_esp_idf::ota::Slot; | ||||
| use esp_bootloader_esp_idf::partitions::DataPartitionSubType::Fat; | ||||
| use esp_hal::delay::Delay; | ||||
| use esp_hal::i2c::master::{BusTimeout, Config, I2c}; | ||||
| use esp_hal::pcnt::unit::Unit; | ||||
| use esp_hal::pcnt::Pcnt; | ||||
| use esp_hal::rng::Rng; | ||||
| use esp_hal::rtc_cntl::{Rtc, SocResetReason}; | ||||
| use esp_hal::system::reset_reason; | ||||
| use esp_hal::time::Rate; | ||||
| use esp_hal::timer::timg::TimerGroup; | ||||
| use esp_hal::twai::Twai; | ||||
| use esp_hal::Blocking; | ||||
| use esp_storage::FlashStorage; | ||||
| use esp_wifi::{init, EspWifiController}; | ||||
| @@ -201,10 +205,9 @@ pub struct FreePeripherals<'a> { | ||||
|     pub gpio29: GPIO29<'a>, | ||||
|     pub gpio30: GPIO30<'a>, | ||||
|     pub twai: TWAI0<'a>, | ||||
|     // pub pcnt0: PCNT0, | ||||
|     // pub pcnt1: PCNT1, | ||||
|     // pub adc1: ADC1, | ||||
|     // pub can: CAN, | ||||
|     pub pcnt0: Unit<'a, 0>, | ||||
|     pub pcnt1: Unit<'a, 1>, | ||||
|     pub adc1: ADC1<'a>, | ||||
| } | ||||
|  | ||||
| macro_rules! mk_static { | ||||
| @@ -255,6 +258,9 @@ impl PlantHal { | ||||
|  | ||||
|         //let mut adc1 = Adc::new(peripherals.ADC1, adc1_config); | ||||
|         // | ||||
|  | ||||
|         let pcnt_module = Pcnt::new(peripherals.PCNT); | ||||
|  | ||||
|         let free_pins = FreePeripherals { | ||||
|             //     can: peripherals.can, | ||||
|             //     adc1: peripherals.adc1, | ||||
| @@ -289,6 +295,9 @@ impl PlantHal { | ||||
|             gpio29: peripherals.GPIO29, | ||||
|             gpio30: peripherals.GPIO30, | ||||
|             twai: peripherals.TWAI0, | ||||
|             pcnt0: pcnt_module.unit0, | ||||
|             pcnt1: pcnt_module.unit1, | ||||
|             adc1: peripherals.ADC1, | ||||
|         }; | ||||
|  | ||||
|         let tablebuffer = mk_static!( | ||||
| @@ -381,7 +390,6 @@ impl PlantHal { | ||||
|             mqtt_client: None, | ||||
|             ota, | ||||
|             ota_next, | ||||
|             wall_clock_offset: 0, | ||||
|         }; | ||||
|  | ||||
|         //init,reset rtc memory depending on cause | ||||
| @@ -574,4 +582,13 @@ pub async fn esp_set_time(time: DateTime<FixedOffset>) { | ||||
|         .get() | ||||
|         .await | ||||
|         .set_current_time_us(time.timestamp_micros() as u64); | ||||
|     BOARD_ACCESS | ||||
|         .get() | ||||
|         .await | ||||
|         .lock() | ||||
|         .await | ||||
|         .board_hal | ||||
|         .get_rtc_module() | ||||
|         .set_rtc_time(&time.to_utc()) | ||||
|         .await; | ||||
| } | ||||
|   | ||||
| @@ -1,13 +1,9 @@ | ||||
| use crate::bail; | ||||
| use crate::hal::Box; | ||||
| use crate::FatError::FatResult; | ||||
| use alloc::vec; | ||||
| use alloc::vec::Vec; | ||||
| use async_trait::async_trait; | ||||
| use bincode::config::Configuration; | ||||
| use bincode::{config, Decode, Encode}; | ||||
| use chrono::{DateTime, Utc}; | ||||
| use crc::Digest; | ||||
| use ds323x::ic::DS3231; | ||||
| use ds323x::interface::I2cInterface; | ||||
| use ds323x::{DateTimeAccess, Ds323x}; | ||||
| @@ -15,12 +11,11 @@ use eeprom24x::addr_size::TwoBytes; | ||||
| use eeprom24x::page_size::B32; | ||||
| use eeprom24x::unique_serial::No; | ||||
| use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice; | ||||
| use embassy_sync::blocking_mutex::raw::{CriticalSectionRawMutex, NoopRawMutex}; | ||||
| use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; | ||||
| use embedded_storage::{ReadStorage, Storage}; | ||||
| use esp_hal::delay::Delay; | ||||
| use esp_hal::i2c::master::I2c; | ||||
| use esp_hal::Blocking; | ||||
| use littlefs2_core::{PathBuf, SeekFrom}; | ||||
| use serde::{Deserialize, Serialize}; | ||||
|  | ||||
| pub const X25: crc::Crc<u16> = crc::Crc::<u16>::new(&crc::CRC_16_IBM_SDLC); | ||||
| @@ -95,7 +90,7 @@ impl RTCModuleInteraction for DS3231Module { | ||||
|             Ok((buf, 0, header.crc16)) | ||||
|         } else { | ||||
|             self.storage.read(offset as u32, &mut buf)?; | ||||
|             let data = &buf[..chunk_size]; | ||||
|             //&buf[..chunk_size]; | ||||
|             Ok((buf, chunk_size, header.crc16)) | ||||
|         } | ||||
|     } | ||||
|   | ||||
| @@ -8,13 +8,15 @@ use alloc::boxed::Box; | ||||
| use async_trait::async_trait; | ||||
| use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice; | ||||
| use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; | ||||
| use esp_hal::analog::adc::{Adc, AdcConfig, Attenuation}; | ||||
| use esp_hal::{twai, Blocking}; | ||||
| //use embedded_hal_bus::i2c::MutexDevice; | ||||
| use crate::bail; | ||||
| use crate::hal::v4_sensor::SensorImpl; | ||||
| use crate::hal::v4_sensor::{SensorImpl, SensorInteraction}; | ||||
| use crate::FatError::{FatError, FatResult}; | ||||
| use esp_hal::gpio::{Flex, Input, InputConfig, Level, Output, OutputConfig}; | ||||
| use esp_hal::gpio::{Flex, Input, InputConfig, Level, Output, OutputConfig, Pull}; | ||||
| use esp_hal::i2c::master::I2c; | ||||
| use esp_hal::pcnt::Pcnt; | ||||
| use esp_hal::twai::{EspTwaiFrame, StandardId, TwaiMode}; | ||||
| use esp_println::println; | ||||
| use ina219::address::{Address, Pin}; | ||||
| @@ -150,20 +152,23 @@ pub(crate) async fn create_v4( | ||||
|     let mut general_fault = Output::new(peripherals.gpio23, Level::Low, OutputConfig::default()); | ||||
|     general_fault.set_low(); | ||||
|  | ||||
|     let mut extra1 = Output::new(peripherals.gpio6, Level::Low, OutputConfig::default()); | ||||
|     let mut extra2 = Output::new(peripherals.gpio15, Level::Low, OutputConfig::default()); | ||||
|     let extra1 = Output::new(peripherals.gpio6, Level::Low, OutputConfig::default()); | ||||
|     let extra2 = Output::new(peripherals.gpio15, Level::Low, OutputConfig::default()); | ||||
|  | ||||
|     let one_wire_pin = Flex::new(peripherals.gpio18); | ||||
|     let tank_power_pin = peripherals.gpio11; | ||||
|     let flow_sensor_pin = peripherals.gpio4; | ||||
|     let tank_power_pin = Output::new(peripherals.gpio11, Level::Low, OutputConfig::default()); | ||||
|     let flow_sensor_pin = Input::new( | ||||
|         peripherals.gpio4, | ||||
|         InputConfig::default().with_pull(Pull::Up), | ||||
|     ); | ||||
|  | ||||
|     let tank_sensor = TankSensor::create( | ||||
|         one_wire_pin, | ||||
|         //peripherals.adc1, | ||||
|         //peripherals.gpio5, | ||||
|         //tank_power_pin, | ||||
|         //flow_sensor_pin, | ||||
|         //peripherals.pcnt1, | ||||
|         peripherals.adc1, | ||||
|         peripherals.gpio5, | ||||
|         tank_power_pin, | ||||
|         flow_sensor_pin, | ||||
|         peripherals.pcnt1, | ||||
|     )?; | ||||
|  | ||||
|     let sensor_expander_device = I2cDevice::new(I2C_DRIVER.get().await); | ||||
| @@ -208,7 +213,7 @@ pub(crate) async fn create_v4( | ||||
|         } | ||||
|         Err(_) => { | ||||
|             log::info!("Can bus mode "); | ||||
|             let mut twai_config = twai::TwaiConfiguration::new( | ||||
|             let twai_config = twai::TwaiConfiguration::new( | ||||
|                 peripherals.twai, | ||||
|                 peripherals.gpio0, | ||||
|                 peripherals.gpio2, | ||||
| @@ -218,9 +223,10 @@ pub(crate) async fn create_v4( | ||||
|  | ||||
|             let mut twai = twai_config.start(); | ||||
|             let frame = EspTwaiFrame::new(StandardId::ZERO, &[1, 2, 3]).unwrap(); | ||||
|  | ||||
|             twai.transmit(&frame).unwrap(); | ||||
|  | ||||
|             let frame = twai.receive().unwrap(); | ||||
|             //            let frame = twai.receive().unwrap(); | ||||
|             println!("Received a frame: {frame:?}"); | ||||
|             //can bus version | ||||
|             SensorImpl::CanBus { twai } | ||||
| @@ -332,8 +338,7 @@ impl<'a> BoardInteraction<'a> for V4<'a> { | ||||
|     } | ||||
|  | ||||
|     fn set_charge_indicator(&mut self, charging: bool) -> Result<(), FatError> { | ||||
|         bail!("not implemented"); | ||||
|         // self.charger.set_charge_indicator(charging) | ||||
|         self.charger.set_charge_indicator(charging) | ||||
|     } | ||||
|  | ||||
|     async fn deep_sleep(&mut self, duration_in_ms: u64) -> ! { | ||||
| @@ -402,8 +407,7 @@ impl<'a> BoardInteraction<'a> for V4<'a> { | ||||
|     } | ||||
|  | ||||
|     async fn measure_moisture_hz(&mut self, plant: usize, sensor: Sensor) -> Result<f32, FatError> { | ||||
|         bail!("not implemented"); | ||||
|         //self.sensor.measure_moisture_hz(plant, sensor) | ||||
|         self.sensor.measure_moisture_hz(plant, sensor).await | ||||
|     } | ||||
|  | ||||
|     async fn general_fault(&mut self, enable: bool) { | ||||
|   | ||||
| @@ -7,11 +7,10 @@ use alloc::string::ToString; | ||||
| use async_trait::async_trait; | ||||
| use embassy_embedded_hal::shared_bus::blocking::i2c::I2cDevice; | ||||
| use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; | ||||
| use embassy_time::{Delay, Timer}; | ||||
| use embassy_time::Timer; | ||||
| use esp_hal::i2c::master::I2c; | ||||
| use esp_hal::twai::Twai; | ||||
| use esp_hal::{Blocking, DriverMode}; | ||||
| use log::log; | ||||
| use esp_hal::Blocking; | ||||
| use pca9535::{GPIOBank, Pca9535Immediate, StandardExpanderInterface}; | ||||
|  | ||||
| const REPEAT_MOIST_MEASURE: usize = 10; | ||||
|   | ||||
| @@ -1,45 +1,40 @@ | ||||
| use crate::bail; | ||||
| use crate::hal::{ADC1, TANK_MULTI_SAMPLE}; | ||||
| use crate::FatError::FatError; | ||||
| use embassy_time::Timer; | ||||
| use esp_hal::analog::adc::{Adc, AdcConfig, AdcPin, Attenuation}; | ||||
| use esp_hal::delay::Delay; | ||||
| use esp_hal::gpio::{Flex, OutputConfig, Pull}; | ||||
| use esp_hal::gpio::{Flex, Input, Output, OutputConfig, Pull}; | ||||
| use esp_hal::pcnt::unit::Unit; | ||||
| use esp_hal::peripherals::GPIO5; | ||||
| use esp_hal::Blocking; | ||||
| use esp_println::println; | ||||
| use littlefs2::object_safe::DynStorage; | ||||
| use onewire::{ds18b20, Device, DeviceSearch, OneWire, DS18B20}; | ||||
|  | ||||
| pub struct TankSensor<'a> { | ||||
|     one_wire_bus: OneWire<Flex<'a>>, | ||||
|     // tank_channel: AdcChannelDriver<'a, Gpio5, AdcDriver<'a, ADC1>>, | ||||
|     // tank_power: PinDriver<'a, AnyIOPin, InputOutput>, | ||||
|     tank_channel: Adc<'a, ADC1<'a>, Blocking>, | ||||
|     tank_power: Output<'a>, | ||||
|     tank_pin: AdcPin<GPIO5<'a>, ADC1<'a>>, | ||||
|     // flow_counter: PcntDriver<'a>, | ||||
|     // delay: Delay, | ||||
| } | ||||
|  | ||||
| impl<'a> TankSensor<'a> { | ||||
|     pub(crate) fn create( | ||||
|         mut one_wire_pin: Flex, | ||||
|         // adc1: ADC1, | ||||
|         // gpio5: Gpio5, | ||||
|         // tank_power_pin: AnyIOPin, | ||||
|         // flow_sensor_pin: AnyIOPin, | ||||
|         // pcnt1: PCNT1, | ||||
|     ) -> Result<TankSensor, FatError> { | ||||
|         mut one_wire_pin: Flex<'a>, | ||||
|         adc1: ADC1<'a>, | ||||
|         gpio5: GPIO5<'a>, | ||||
|         tank_power: Output<'a>, | ||||
|         flow_sensor: Input, | ||||
|         pcnt1: Unit<'a, 1>, | ||||
|     ) -> Result<TankSensor<'a>, FatError> { | ||||
|         one_wire_pin.apply_output_config(&OutputConfig::default().with_pull(Pull::None)); | ||||
|  | ||||
|         // let adc_config = AdcChannelConfig { | ||||
|         //     attenuation: attenuation::DB_11, | ||||
|         //     resolution: Resolution::Resolution12Bit, | ||||
|         //     calibration: esp_idf_hal::adc::oneshot::config::Calibration::Curve, | ||||
|         // }; | ||||
|         // let tank_driver = AdcDriver::new(adc1).expect("Failed to configure ADC"); | ||||
|         // let tank_channel = AdcChannelDriver::new(tank_driver, gpio5, &adc_config) | ||||
|         //     .expect("Failed to configure ADC channel"); | ||||
|         // | ||||
|         // let mut tank_power = | ||||
|         //     PinDriver::input_output(tank_power_pin).expect("Failed to configure pin"); | ||||
|         // tank_power | ||||
|         //     .set_pull(Pull::Floating) | ||||
|         //     .expect("Failed to set pull"); | ||||
|         // | ||||
|         let mut adc1_config = AdcConfig::new(); | ||||
|         let tank_pin = adc1_config.enable_pin(gpio5, Attenuation::_11dB); | ||||
|         let mut tank_channel = Adc::new(adc1, adc1_config); | ||||
|  | ||||
|         let one_wire_bus = OneWire::new(one_wire_pin, false); | ||||
|  | ||||
| @@ -68,10 +63,10 @@ impl<'a> TankSensor<'a> { | ||||
|         // | ||||
|         Ok(TankSensor { | ||||
|             one_wire_bus, | ||||
|             //     tank_channel, | ||||
|             //     tank_power, | ||||
|             //     flow_counter, | ||||
|             //     delay: Default::default(), | ||||
|             tank_channel, | ||||
|             tank_power, | ||||
|             tank_pin, //     flow_counter, | ||||
|                       //     delay: Default::default(), | ||||
|         }) | ||||
|     } | ||||
|  | ||||
| @@ -153,20 +148,24 @@ impl<'a> TankSensor<'a> { | ||||
|     } | ||||
|  | ||||
|     pub async fn tank_sensor_voltage(&mut self) -> Result<f32, FatError> { | ||||
|         // self.tank_power.set_high()?; | ||||
|         // //let stabilize | ||||
|         // self.delay.delay_ms(100); | ||||
|         // | ||||
|         // let mut store = [0_u16; TANK_MULTI_SAMPLE]; | ||||
|         // for multisample in 0..TANK_MULTI_SAMPLE { | ||||
|         //     let value = self.tank_channel.read()?; | ||||
|         //     store[multisample] = value; | ||||
|         // } | ||||
|         // self.tank_power.set_low()?; | ||||
|         // | ||||
|         // store.sort(); | ||||
|         // let median_mv = store[6] as f32 / 1000_f32; | ||||
|         let median_mv = 10_f32; | ||||
|         self.tank_power.set_high(); | ||||
|         //let stabilize | ||||
|         Timer::after_millis(100).await; | ||||
|  | ||||
|         let mut store = [0_u16; TANK_MULTI_SAMPLE]; | ||||
|         for multisample in 0..TANK_MULTI_SAMPLE { | ||||
|             let mut asy = (&mut self.tank_channel); | ||||
|  | ||||
|             let value = asy.read_oneshot(&mut self.tank_pin); | ||||
|             //force yield | ||||
|             Timer::after_millis(10).await; | ||||
|             store[multisample] = value.unwrap(); | ||||
|         } | ||||
|         self.tank_power.set_low(); | ||||
|  | ||||
|         store.sort(); | ||||
|         //TODO probably wrong? check! | ||||
|         let median_mv = store[6] as f32 * 3300_f32 / 4096_f32; | ||||
|         Ok(median_mv) | ||||
|     } | ||||
| } | ||||
|   | ||||
| @@ -13,7 +13,7 @@ esp_bootloader_esp_idf::esp_app_desc!(); | ||||
| use esp_backtrace as _; | ||||
|  | ||||
| use crate::config::PlantConfig; | ||||
| use crate::hal::esp_time; | ||||
| use crate::hal::{esp_time, TIME_ACCESS}; | ||||
| use crate::log::LOG_ACCESS; | ||||
| use crate::tank::{determine_tank_state, TankError, WATER_FROZEN_THRESH}; | ||||
| use crate::webserver::httpd; | ||||
| @@ -22,7 +22,7 @@ use crate::{ | ||||
|     config::BoardVersion::INITIAL, | ||||
|     hal::{PlantHal, HAL, PLANT_COUNT}, | ||||
| }; | ||||
| use ::log::{error, info, warn}; | ||||
| use ::log::{info, warn}; | ||||
| use alloc::borrow::ToOwned; | ||||
| use alloc::string::{String, ToString}; | ||||
| use alloc::sync::Arc; | ||||
| @@ -35,7 +35,6 @@ use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex; | ||||
| use embassy_sync::mutex::{Mutex, MutexGuard}; | ||||
| use embassy_sync::once_lock::OnceLock; | ||||
| use embassy_time::Timer; | ||||
| use esp_bootloader_esp_idf::ota::OtaImageState; | ||||
| use esp_hal::rom::ets_delay_us; | ||||
| use esp_hal::system::software_reset; | ||||
| use esp_println::{logger, println}; | ||||
| @@ -163,7 +162,13 @@ async fn safe_main(spawner: Spawner) -> FatResult<()> { | ||||
|  | ||||
|     board.board_hal.general_fault(false).await; | ||||
|     let cur = match board.board_hal.get_rtc_module().get_rtc_time().await { | ||||
|         Ok(value) => value, | ||||
|         Ok(value) => { | ||||
|             TIME_ACCESS | ||||
|                 .get() | ||||
|                 .await | ||||
|                 .set_current_time_us(value.timestamp_micros() as u64); | ||||
|             value | ||||
|         } | ||||
|         Err(err) => { | ||||
|             info!("rtc module error: {:?}", err); | ||||
|             board.board_hal.general_fault(true).await; | ||||
|   | ||||
| @@ -4,7 +4,7 @@ use crate::config::PlantControllerConfig; | ||||
| use crate::hal::rtc::X25; | ||||
| use crate::hal::{esp_set_time, esp_time}; | ||||
| use crate::log::LOG_ACCESS; | ||||
| use crate::tank::{determine_tank_state, TankInfo}; | ||||
| use crate::tank::determine_tank_state; | ||||
| use crate::FatError::{FatError, FatResult}; | ||||
| use crate::{bail, get_version, log::LogMessage, BOARD_ACCESS}; | ||||
| use alloc::borrow::ToOwned; | ||||
| @@ -385,7 +385,7 @@ impl Handler for HttpHandler { | ||||
|                         Some(200) | ||||
|                     } | ||||
|                     "/log" => { | ||||
|                         let buf = get_log(conn).await; | ||||
|                         get_log(conn).await?; | ||||
|                         Some(200) | ||||
|                     } | ||||
|                     "/get_backup_config" => { | ||||
| @@ -688,12 +688,11 @@ async fn wifi_scan<T, const N: usize>( | ||||
| ) -> FatResult<Option<String>> { | ||||
|     let mut board = BOARD_ACCESS.get().await.lock().await; | ||||
|     info!("start wifi scan"); | ||||
|     //let scan_result = board.board_hal.get_esp().wifi_scan().await? | ||||
|     //FIXME currently panics | ||||
|     let mut ssids: Vec<String> = Vec::new(); | ||||
|     //scan_result | ||||
|     //.iter() | ||||
|     //.for_each(|s| ssids.push(s.ssid.to_string())); | ||||
|     let scan_result = board.board_hal.get_esp().wifi_scan().await?; | ||||
|     scan_result | ||||
|         .iter() | ||||
|         .for_each(|s| ssids.push(s.ssid.to_string())); | ||||
|     let ssid_json = serde_json::to_string(&SSIDList { ssids })?; | ||||
|     info!("Sending ssid list {}", &ssid_json); | ||||
|     Ok(Some(ssid_json)) | ||||
|   | ||||
		Reference in New Issue
	
	Block a user