7 Commits

11 changed files with 245097 additions and 171491 deletions

File diff suppressed because it is too large Load Diff

View File

@@ -1,6 +1,6 @@
{ {
"board": { "board": {
"active_layer": 2, "active_layer": 39,
"active_layer_preset": "", "active_layer_preset": "",
"auto_track_width": false, "auto_track_width": false,
"hidden_netclasses": [], "hidden_netclasses": [],
@@ -68,9 +68,15 @@
39, 39,
40 40
], ],
"visible_layers": "fffffff_ffffffff", "visible_layers": "ffdfffe_ffffffff",
"zone_display_mode": 1 "zone_display_mode": 1
}, },
"git": {
"repo_password": "",
"repo_type": "",
"repo_username": "",
"ssh_key": ""
},
"meta": { "meta": {
"filename": "PlantCtrlESP32.kicad_prl", "filename": "PlantCtrlESP32.kicad_prl",
"version": 3 "version": 3

View File

@@ -3,14 +3,17 @@
"3dviewports": [], "3dviewports": [],
"design_settings": { "design_settings": {
"defaults": { "defaults": {
"board_outline_line_width": 0.049999999999999996, "apply_defaults_to_fp_fields": false,
"copper_line_width": 0.19999999999999998, "apply_defaults_to_fp_shapes": false,
"apply_defaults_to_fp_text": false,
"board_outline_line_width": 0.05,
"copper_line_width": 0.2,
"copper_text_italic": false, "copper_text_italic": false,
"copper_text_size_h": 1.5, "copper_text_size_h": 1.5,
"copper_text_size_v": 1.5, "copper_text_size_v": 1.5,
"copper_text_thickness": 0.3, "copper_text_thickness": 0.3,
"copper_text_upright": false, "copper_text_upright": false,
"courtyard_line_width": 0.049999999999999996, "courtyard_line_width": 0.05,
"dimension_precision": 4, "dimension_precision": 4,
"dimension_units": 3, "dimension_units": 3,
"dimensions": { "dimensions": {
@@ -21,13 +24,13 @@
"text_position": 0, "text_position": 0,
"units_format": 1 "units_format": 1
}, },
"fab_line_width": 0.09999999999999999, "fab_line_width": 0.1,
"fab_text_italic": false, "fab_text_italic": false,
"fab_text_size_h": 1.0, "fab_text_size_h": 1.0,
"fab_text_size_v": 1.0, "fab_text_size_v": 1.0,
"fab_text_thickness": 0.15, "fab_text_thickness": 0.15,
"fab_text_upright": false, "fab_text_upright": false,
"other_line_width": 0.09999999999999999, "other_line_width": 0.1,
"other_text_italic": false, "other_text_italic": false,
"other_text_size_h": 1.0, "other_text_size_h": 1.0,
"other_text_size_v": 1.0, "other_text_size_v": 1.0,
@@ -73,6 +76,7 @@
"duplicate_footprints": "warning", "duplicate_footprints": "warning",
"extra_footprint": "warning", "extra_footprint": "warning",
"footprint": "error", "footprint": "error",
"footprint_symbol_mismatch": "warning",
"footprint_type_mismatch": "ignore", "footprint_type_mismatch": "ignore",
"hole_clearance": "error", "hole_clearance": "error",
"hole_near_hole": "error", "hole_near_hole": "error",
@@ -116,27 +120,24 @@
"max_error": 0.005, "max_error": 0.005,
"min_clearance": 0.0, "min_clearance": 0.0,
"min_connection": 0.0, "min_connection": 0.0,
"min_copper_edge_clearance": 0.024999999999999998, "min_copper_edge_clearance": 0.025,
"min_hole_clearance": 0.25, "min_hole_clearance": 0.25,
"min_hole_to_hole": 0.25, "min_hole_to_hole": 0.25,
"min_microvia_diameter": 0.19999999999999998, "min_microvia_diameter": 0.2,
"min_microvia_drill": 0.09999999999999999, "min_microvia_drill": 0.1,
"min_resolved_spokes": 1, "min_resolved_spokes": 1,
"min_silk_clearance": 0.0, "min_silk_clearance": 0.0,
"min_text_height": 0.7999999999999999, "min_text_height": 0.8,
"min_text_thickness": 0.08, "min_text_thickness": 0.08,
"min_through_hole_diameter": 0.19999999999999998, "min_through_hole_diameter": 0.2,
"min_track_width": 0.19999999999999998, "min_track_width": 0.2,
"min_via_annular_width": 0.09999999999999999, "min_via_annular_width": 0.1,
"min_via_diameter": 0.39999999999999997, "min_via_diameter": 0.4,
"solder_mask_to_copper_clearance": 0.005, "solder_mask_to_copper_clearance": 0.005,
"use_height_for_length_calcs": true "use_height_for_length_calcs": true
}, },
"teardrop_options": [ "teardrop_options": [
{ {
"td_allow_use_two_tracks": true,
"td_curve_segcount": 5,
"td_on_pad_in_zone": false,
"td_onpadsmd": true, "td_onpadsmd": true,
"td_onroundshapesonly": false, "td_onroundshapesonly": false,
"td_ontrackend": false, "td_ontrackend": false,
@@ -145,29 +146,35 @@
], ],
"teardrop_parameters": [ "teardrop_parameters": [
{ {
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0, "td_curve_segcount": 0,
"td_height_ratio": 1.0, "td_height_ratio": 1.0,
"td_length_ratio": 0.5, "td_length_ratio": 0.5,
"td_maxheight": 2.0, "td_maxheight": 2.0,
"td_maxlen": 1.0, "td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_round_shape", "td_target_name": "td_round_shape",
"td_width_to_size_filter_ratio": 0.9 "td_width_to_size_filter_ratio": 0.9
}, },
{ {
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0, "td_curve_segcount": 0,
"td_height_ratio": 1.0, "td_height_ratio": 1.0,
"td_length_ratio": 0.5, "td_length_ratio": 0.5,
"td_maxheight": 2.0, "td_maxheight": 2.0,
"td_maxlen": 1.0, "td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_rect_shape", "td_target_name": "td_rect_shape",
"td_width_to_size_filter_ratio": 0.9 "td_width_to_size_filter_ratio": 0.9
}, },
{ {
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0, "td_curve_segcount": 0,
"td_height_ratio": 1.0, "td_height_ratio": 1.0,
"td_length_ratio": 0.5, "td_length_ratio": 0.5,
"td_maxheight": 2.0, "td_maxheight": 2.0,
"td_maxlen": 1.0, "td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_track_end", "td_target_name": "td_track_end",
"td_width_to_size_filter_ratio": 0.9 "td_width_to_size_filter_ratio": 0.9
} }
@@ -180,6 +187,32 @@
1.5, 1.5,
2.0 2.0
], ],
"tuning_pattern_settings": {
"diff_pair_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 1.0
},
"diff_pair_skew_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
},
"single_track_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
}
},
"via_dimensions": [ "via_dimensions": [
{ {
"diameter": 0.0, "diameter": 0.0,
@@ -197,6 +230,13 @@
"zones_allow_external_fillets": true, "zones_allow_external_fillets": true,
"zones_use_no_outline": true "zones_use_no_outline": true
}, },
"ipc2581": {
"dist": "",
"distpn": "",
"internal_id": "",
"mfg": "",
"mpn": ""
},
"layer_presets": [], "layer_presets": [],
"viewports": [] "viewports": []
}, },
@@ -1000,14 +1040,75 @@
"gencad": "", "gencad": "",
"idf": "", "idf": "",
"netlist": "PlantCtrlESP32.net", "netlist": "PlantCtrlESP32.net",
"plot": "",
"pos_files": "",
"specctra_dsn": "", "specctra_dsn": "",
"step": "", "step": "",
"svg": "",
"vrml": "" "vrml": ""
}, },
"page_layout_descr_file": "" "page_layout_descr_file": ""
}, },
"schematic": { "schematic": {
"annotate_start_num": 0, "annotate_start_num": 0,
"bom_fmt_presets": [],
"bom_fmt_settings": {
"field_delimiter": ",",
"keep_line_breaks": false,
"keep_tabs": false,
"name": "CSV",
"ref_delimiter": ",",
"ref_range_delimiter": "",
"string_delimiter": "\""
},
"bom_presets": [],
"bom_settings": {
"exclude_dnp": false,
"fields_ordered": [
{
"group_by": false,
"label": "Reference",
"name": "Reference",
"show": true
},
{
"group_by": true,
"label": "Value",
"name": "Value",
"show": true
},
{
"group_by": false,
"label": "Datasheet",
"name": "Datasheet",
"show": true
},
{
"group_by": false,
"label": "Footprint",
"name": "Footprint",
"show": true
},
{
"group_by": false,
"label": "Qty",
"name": "${QUANTITY}",
"show": true
},
{
"group_by": true,
"label": "DNP",
"name": "${DNP}",
"show": true
}
],
"filter_string": "",
"group_symbols": true,
"name": "Grouped By Value",
"sort_asc": true,
"sort_field": "Reference"
},
"connection_grid_size": 50.0,
"drawing": { "drawing": {
"dashed_lines_dash_length_ratio": 12.0, "dashed_lines_dash_length_ratio": 12.0,
"dashed_lines_gap_length_ratio": 3.0, "dashed_lines_gap_length_ratio": 3.0,
@@ -1021,6 +1122,11 @@
"intersheets_ref_suffix": "", "intersheets_ref_suffix": "",
"junction_size_choice": 3, "junction_size_choice": 3,
"label_size_ratio": 0.25, "label_size_ratio": 0.25,
"operating_point_overlay_i_precision": 3,
"operating_point_overlay_i_range": "~A",
"operating_point_overlay_v_precision": 3,
"operating_point_overlay_v_range": "~V",
"overbar_offset_ratio": 1.23,
"pin_symbol_size": 0.0, "pin_symbol_size": 0.0,
"text_offset_ratio": 0.08 "text_offset_ratio": 0.08
}, },
@@ -1046,6 +1152,7 @@
"spice_external_command": "spice \"%I\"", "spice_external_command": "spice \"%I\"",
"spice_model_current_sheet_as_root": true, "spice_model_current_sheet_as_root": true,
"spice_save_all_currents": false, "spice_save_all_currents": false,
"spice_save_all_dissipations": false,
"spice_save_all_voltages": false, "spice_save_all_voltages": false,
"subpart_first_id": 65, "subpart_first_id": 65,
"subpart_id_separator": 0 "subpart_id_separator": 0
@@ -1053,7 +1160,7 @@
"sheets": [ "sheets": [
[ [
"c26e8d55-0b6e-4c4e-b7c8-b1fed973201c", "c26e8d55-0b6e-4c4e-b7c8-b1fed973201c",
"" "Root"
] ]
], ],
"text_variables": {} "text_variables": {}

File diff suppressed because it is too large Load Diff

View File

@@ -1,6 +1,6 @@
use std::sync::{atomic::AtomicBool, Arc, Mutex}; use std::sync::{atomic::AtomicBool, Arc, Mutex};
use chrono::{DateTime, Datelike, Duration, NaiveDateTime, Timelike}; use chrono::{DateTime, Datelike, TimeDelta, Timelike};
use chrono_tz::{Europe::Berlin, Tz}; use chrono_tz::{Europe::Berlin, Tz};
use esp_idf_hal::delay::Delay; use esp_idf_hal::delay::Delay;
@@ -61,11 +61,12 @@ struct LightState {
is_day: bool, is_day: bool,
} }
#[derive(Copy, Clone, Debug, PartialEq, Default)] #[derive(Clone, Copy, Debug, PartialEq, Default)]
struct PlantState { struct PlantState {
a: Option<u8>, a: Option<u8>,
b: Option<u8>, b: Option<u8>,
p: Option<u8>, p: Option<u8>,
consecutive_pump_count: u32,
after_p: Option<u8>, after_p: Option<u8>,
do_water: bool, do_water: bool,
frozen: bool, frozen: bool,
@@ -168,7 +169,7 @@ fn safe_main() -> anyhow::Result<()> {
Ok(cur) => cur, Ok(cur) => cur,
Err(err) => { Err(err) => {
log::error!("time error {}", err); log::error!("time error {}", err);
NaiveDateTime::from_timestamp_millis(0).unwrap().and_utc() DateTime::from_timestamp_millis(0).unwrap()
} }
}; };
//check if we know the time current > 2020 //check if we know the time current > 2020
@@ -325,38 +326,49 @@ fn safe_main() -> anyhow::Result<()> {
let mut water_frozen = false; let mut water_frozen = false;
let mut temp:Option<f32> = None;
for _attempt in 0..5 { for _attempt in 0..5 {
let water_temperature = board.water_temperature_c(); let water_temperature = board.water_temperature_c();
match water_temperature { match water_temperature {
Ok(temp) => { Ok(res) => {
if online_mode == OnlineMode::Online { temp = Some(res);
let _ = board.mqtt_publish(
&config,
"/water/temperature",
temp.to_string().as_bytes(),
);
}
//FIXME mqtt here
println!("Water temp is {}", temp);
if temp < 4_f32 {
water_frozen = true;
}
break; break;
} }
Err(err) => { Err(err) => {
if online_mode == OnlineMode::Online { println!("Could not get water temp {} attempt {}", err, _attempt)
let _ = board.mqtt_publish(&config, "/water/temperature", "Error".as_bytes());
}
println!("Could not get water temp {}", err)
} }
} }
} }
match temp {
Some(res) => {
println!("Water temp is {}", res);
if res < 4_f32 {
water_frozen = true;
}
if online_mode == OnlineMode::Online {
let _ = board.mqtt_publish(
&config,
"/water/temperature",
res.to_string().as_bytes(),
);
}
},
None => {
if online_mode == OnlineMode::Online {
let _ = board.mqtt_publish(&config, "/water/temperature", "Error".as_bytes());
}
},
}
let mut plantstate = [PlantState { let mut plantstate = [PlantState {
..Default::default() ..Default::default()
}; PLANT_COUNT]; }; PLANT_COUNT];
let plant_to_pump = determine_next_plant( let plant_to_pump = determine_next_plant(
online_mode,
&mut plantstate, &mut plantstate,
europe_time, europe_time,
&tank_state, &tank_state,
@@ -371,12 +383,17 @@ fn safe_main() -> anyhow::Result<()> {
let _webserver = httpd(reboot_now.clone()); let _webserver = httpd(reboot_now.clone());
wait_infinity(WaitType::StayAlive, reboot_now.clone()); wait_infinity(WaitType::StayAlive, reboot_now.clone());
} }
let mut did_pump = false;
match plant_to_pump { match plant_to_pump {
Some(plant) => { Some(plant) => {
let mut state = plantstate[plant]; let state = &mut plantstate[plant];
let consecutive_pump_count = board.consecutive_pump_count(plant) + 1; state.consecutive_pump_count = board.consecutive_pump_count(plant) + 1;
board.store_consecutive_pump_count(plant, consecutive_pump_count); board.store_consecutive_pump_count(plant, state.consecutive_pump_count);
if state.consecutive_pump_count > config.max_consecutive_pump_count.into() {
state.not_effective = true;
board.fault(plant, true);
}
let plant_config = config.plants[plant]; let plant_config = config.plants[plant];
if plant_config.sensor_p { if plant_config.sensor_p {
@@ -395,7 +412,7 @@ fn safe_main() -> anyhow::Result<()> {
"Trying to pump for {}s with pump {} now", "Trying to pump for {}s with pump {} now",
plant_config.pump_time_s, plant plant_config.pump_time_s, plant
); );
did_pump = true;
board.any_pump(true)?; board.any_pump(true)?;
board.store_last_pump_time(plant, cur); board.store_last_pump_time(plant, cur);
board.pump(plant, true)?; board.pump(plant, true)?;
@@ -522,14 +539,25 @@ fn safe_main() -> anyhow::Result<()> {
} }
12 * 60 12 * 60
} else if is_day { } else if is_day {
if online_mode == OnlineMode::Online { if did_pump {
let _ = board.mqtt_publish( if online_mode == OnlineMode::Online {
&config, let _ = board.mqtt_publish(
"/deepsleep", &config,
"normal 20m".as_bytes(), "/deepsleep",
); "after pump".as_bytes(),
);
}
0
} else {
if online_mode == OnlineMode::Online {
let _ = board.mqtt_publish(
&config,
"/deepsleep",
"normal 20m".as_bytes(),
);
}
20
} }
20
} else { } else {
if online_mode == OnlineMode::Online { if online_mode == OnlineMode::Online {
let _ = board.mqtt_publish( let _ = board.mqtt_publish(
@@ -549,7 +577,6 @@ fn safe_main() -> anyhow::Result<()> {
//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(); mark_app_valid();
unsafe { esp_deep_sleep(1000 * 1000 * 60 * deep_sleep_duration_minutes as u64) }; unsafe { esp_deep_sleep(1000 * 1000 * 60 * deep_sleep_duration_minutes as u64) };
@@ -835,7 +862,7 @@ fn determine_state_target_moisture_for_plant(
state.no_water = true; state.no_water = true;
} }
} }
let duration = Duration::minutes((plant_config.pump_cooldown_min).into()); let duration = TimeDelta::try_minutes(plant_config.pump_cooldown_min as i64).unwrap();
let next_pump = board.last_pump_time(plant) + duration; let next_pump = board.last_pump_time(plant) + duration;
if next_pump > cur { if next_pump > cur {
let europe_time = next_pump.with_timezone(&Berlin); let europe_time = next_pump.with_timezone(&Berlin);
@@ -862,7 +889,6 @@ fn determine_state_target_moisture_for_plant(
} }
fn determine_next_plant( fn determine_next_plant(
online_mode: OnlineMode,
plantstate: &mut [PlantState; PLANT_COUNT], plantstate: &mut [PlantState; PLANT_COUNT],
cur: DateTime<Tz>, cur: DateTime<Tz>,
tank_state: &TankState, tank_state: &TankState,
@@ -887,7 +913,7 @@ fn determine_next_plant(
); );
} }
config::Mode::TimerOnly => { config::Mode::TimerOnly => {
let duration = Duration::minutes((plant_config.pump_cooldown_min).into()); let duration = TimeDelta::try_minutes(plant_config.pump_cooldown_min as i64).unwrap();
let next_pump = board.last_pump_time(plant) + duration; let next_pump = board.last_pump_time(plant) + duration;
if next_pump > cur { if next_pump > cur {
let europe_time = next_pump.with_timezone(&Berlin); let europe_time = next_pump.with_timezone(&Berlin);
@@ -902,7 +928,7 @@ fn determine_next_plant(
} }
} }
config::Mode::TimerAndDeadzone => { config::Mode::TimerAndDeadzone => {
let duration = Duration::minutes((60 * plant_config.pump_cooldown_min).into()); let duration = TimeDelta::try_minutes(plant_config.pump_cooldown_min as i64).unwrap();
let next_pump = board.last_pump_time(plant) + duration; let next_pump = board.last_pump_time(plant) + duration;
if next_pump > cur { if next_pump > cur {
let europe_time = next_pump.with_timezone(&Berlin); let europe_time = next_pump.with_timezone(&Berlin);
@@ -932,19 +958,12 @@ fn determine_next_plant(
{ {
board.fault(plant, true); board.fault(plant, true);
} }
if state.do_water { if !state.dry {
if board.consecutive_pump_count(plant) > config.max_consecutive_pump_count.into() { state.consecutive_pump_count = 0;
state.not_effective = true;
board.fault(plant, true);
}
} else {
board.store_consecutive_pump_count(plant, 0); board.store_consecutive_pump_count(plant, 0);
} }
println!("Plant {} state is {:?}", plant, state); println!("Plant {} state is {:?}", plant, state);
} }
if online_mode == OnlineMode::Online {
update_plant_state(plantstate, board, config);
}
for plant in 0..PLANT_COUNT { for plant in 0..PLANT_COUNT {
let state = &plantstate[plant]; let state = &plantstate[plant];
println!( println!(
@@ -1013,7 +1032,11 @@ fn update_plant_state(
); );
} }
} }
let _ = board.mqtt_publish(
&config,
format!("/plant{}/active", plant + 1).as_str(),
state.active.to_string().as_bytes(),
);
let _ = board.mqtt_publish( let _ = board.mqtt_publish(
&config, &config,
format!("/plant{}/Sensor A", plant + 1).as_str(), format!("/plant{}/Sensor A", plant + 1).as_str(),
@@ -1097,6 +1120,13 @@ fn update_plant_state(
format!("/plant{}/Out of Work Hour", plant + 1).as_str(), format!("/plant{}/Out of Work Hour", plant + 1).as_str(),
state.out_of_work_hour.to_string().as_bytes(), state.out_of_work_hour.to_string().as_bytes(),
); );
let _ = board.mqtt_publish(
&config,
format!("/plant{}/consecutive pump count", plant + 1).as_str(),
state.consecutive_pump_count.to_string().as_bytes(),
);
} }
} }

View File

@@ -23,7 +23,7 @@ use std::ffi::CString;
use std::fs::File; use std::fs::File;
use std::path::Path; use std::path::Path;
use chrono::{DateTime, NaiveDateTime, Utc}; use chrono::{DateTime, Utc};
use ds18b20::Ds18b20; use ds18b20::Ds18b20;
use std::result::Result::Ok as OkStd; use std::result::Result::Ok as OkStd;
use std::str::FromStr; use std::str::FromStr;
@@ -83,6 +83,7 @@ pub enum ClearConfigType {
} }
#[derive(Debug)] #[derive(Debug)]
#[derive(PartialEq)]
pub enum Sensor { pub enum Sensor {
A, A,
B, B,
@@ -143,6 +144,7 @@ pub trait PlantCtrlBoardInteraction {
fn wifi_ap(&mut self) -> Result<()>; fn wifi_ap(&mut self) -> Result<()>;
fn wifi_scan(&mut self) -> Result<Vec<AccessPointInfo>>; fn wifi_scan(&mut self) -> Result<Vec<AccessPointInfo>>;
fn test(&mut self) -> Result<()>; fn test(&mut self) -> Result<()>;
fn test_pump(&mut self, plant:usize) -> Result<()>;
fn is_wifi_config_file_existant(&mut self) -> bool; fn is_wifi_config_file_existant(&mut self) -> bool;
fn mqtt(&mut self, config: &Config) -> Result<()>; fn mqtt(&mut self, config: &Config) -> Result<()>;
fn mqtt_publish(&mut self, config: &Config, subtopic: &str, message: &[u8]) -> Result<()>; fn mqtt_publish(&mut self, config: &Config, subtopic: &str, message: &[u8]) -> Result<()>;
@@ -240,12 +242,11 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
let mut percent = r2 / 190_f32 * 100_f32; let mut percent = r2 / 190_f32 * 100_f32;
percent = percent.clamp(0.0, 100.0); percent = percent.clamp(0.0, 100.0);
let quantizised = quantize_to_next_5_percent(percent as f64) as u16;
println!( println!(
"Tank sensor raw {} percent {} quantized {}", "Tank sensor raw {} percent {}",
median, percent, quantizised median, percent
); );
return Ok(quantizised); return Ok(percent as u16);
} }
fn set_low_voltage_in_cycle(&mut self) { fn set_low_voltage_in_cycle(&mut self) {
@@ -278,8 +279,7 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
fn last_pump_time(&self, plant: usize) -> chrono::DateTime<Utc> { fn last_pump_time(&self, plant: usize) -> chrono::DateTime<Utc> {
let ts = unsafe { LAST_WATERING_TIMESTAMP }[plant]; let ts = unsafe { LAST_WATERING_TIMESTAMP }[plant];
let timestamp = NaiveDateTime::from_timestamp_millis(ts).unwrap(); return DateTime::from_timestamp_millis(ts).unwrap();
DateTime::<Utc>::from_naive_utc_and_offset(timestamp, Utc)
} }
fn store_last_pump_time(&mut self, plant: usize, time: chrono::DateTime<Utc>) { fn store_last_pump_time(&mut self, plant: usize, time: chrono::DateTime<Utc>) {
@@ -323,9 +323,9 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
fn time(&mut self) -> Result<chrono::DateTime<Utc>> { fn time(&mut self) -> Result<chrono::DateTime<Utc>> {
let time = EspSystemTime {}.now().as_millis(); let time = EspSystemTime {}.now().as_millis();
let smaller_time = time as i64; let smaller_time = time as i64;
let local_time = NaiveDateTime::from_timestamp_millis(smaller_time) let local_time = DateTime::from_timestamp_millis(smaller_time)
.ok_or(anyhow!("could not convert timestamp"))?; .ok_or(anyhow!("could not convert timestamp"))?;
Ok(local_time.and_utc()) Ok(local_time)
} }
fn sntp(&mut self, max_wait_ms: u32) -> Result<chrono::DateTime<Utc>> { fn sntp(&mut self, max_wait_ms: u32) -> Result<chrono::DateTime<Utc>> {
@@ -359,12 +359,20 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
let factor = 1000 as f32 / measurement as f32; let factor = 1000 as f32 / measurement as f32;
self.shift_register.decompose()[index].set_high().unwrap(); self.shift_register.decompose()[index].set_high().unwrap();
if plant == 0 && sensor == Sensor::A {
let index = plant * PINS_PER_PLANT + PLANT_MOIST_PUMP_OFFSET;
//self.shift_register.decompose()[index].set_high().unwrap();
}
//give some time to stabilize //give some time to stabilize
delay.delay_ms(10); delay.delay_ms(10);
self.signal_counter.counter_resume()?; self.signal_counter.counter_resume()?;
delay.delay_ms(measurement); delay.delay_ms(measurement);
self.signal_counter.counter_pause()?; self.signal_counter.counter_pause()?;
self.shift_register.decompose()[index].set_low().unwrap(); self.shift_register.decompose()[index].set_low().unwrap();
if plant == 0 && sensor == Sensor::A {
let index = plant * PINS_PER_PLANT + PLANT_MOIST_PUMP_OFFSET;
//self.shift_register.decompose()[index].set_low().unwrap();
}
let unscaled = self.signal_counter.get_counter_value()? as i32; let unscaled = self.signal_counter.get_counter_value()? as i32;
let hz = (unscaled as f32 * factor) as i32; let hz = (unscaled as f32 * factor) as i32;
println!("Measuring {:?} @ {} with {}", sensor, plant, hz); println!("Measuring {:?} @ {} with {}", sensor, plant, hz);
@@ -568,6 +576,15 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
Ok(self.wifi_driver.get_scan_result()?) Ok(self.wifi_driver.get_scan_result()?)
} }
fn test_pump(&mut self, plant:usize) -> Result<()> {
self.any_pump(true)?;
self.pump(plant, true)?;
unsafe { vTaskDelay(30000) };
self.pump(plant, false)?;
self.any_pump(false)?;
Ok(())
}
fn test(&mut self) -> Result<()> { fn test(&mut self) -> Result<()> {
self.general_fault(true); self.general_fault(true);
unsafe { vTaskDelay(100) }; unsafe { vTaskDelay(100) };
@@ -717,14 +734,25 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
println!("Some error assembling full_topic 2"); println!("Some error assembling full_topic 2");
bail!("Some error assembling full_topic 2") bail!("Some error assembling full_topic 2")
}; };
client.publish( let publish = client.publish(
&full_topic, &full_topic,
embedded_svc::mqtt::client::QoS::ExactlyOnce, embedded_svc::mqtt::client::QoS::ExactlyOnce,
true, true,
message, message,
)?; );
Delay::new(10).delay_ms(50);
match publish {
OkStd(message_id) => {
println!("Published mqtt topic {} with message {:#?} msgid is {:?}",full_topic, String::from_utf8_lossy(message), message_id);
return Ok(())
},
Err(err) => {
println!("Error during mqtt send on topic {} with message {:#?} error is {:?}",full_topic, String::from_utf8_lossy(message), err);
return Err(err)?
},
}
return Ok(()); ;
} }
fn state_charge_percent(&mut self) -> Result<u8> { fn state_charge_percent(&mut self) -> Result<u8> {
@@ -782,6 +810,7 @@ impl PlantCtrlBoardInteraction for PlantCtrlBoard<'_> {
Err(err) => bail!("Error reading State of Health {:?}", err), Err(err) => bail!("Error reading State of Health {:?}", err),
} }
} }
} }
fn print_battery( fn print_battery(
@@ -910,9 +939,8 @@ impl CreatePlantHal<'_> for PlantHal {
); );
for i in 0..PLANT_COUNT { for i in 0..PLANT_COUNT {
let smaller_time = LAST_WATERING_TIMESTAMP[i]; let smaller_time = LAST_WATERING_TIMESTAMP[i];
let local_time = NaiveDateTime::from_timestamp_millis(smaller_time) let utc_time = DateTime::from_timestamp_millis(smaller_time)
.ok_or(anyhow!("could not convert timestamp"))?; .ok_or(anyhow!("could not convert timestamp"))?;
let utc_time = local_time.and_utc();
let europe_time = utc_time.with_timezone(&Berlin); let europe_time = utc_time.with_timezone(&Berlin);
println!( println!(
@@ -1018,21 +1046,3 @@ impl CreatePlantHal<'_> for PlantHal {
Ok(rv) Ok(rv)
} }
} }
fn quantize_to_next_5_percent(value: f64) -> i32 {
// Multiply by 100 to work with integer values
let multiplied_value = (value * 100.0).round() as i32;
// Calculate the remainder when divided by 5
let remainder = multiplied_value % 5;
// If the remainder is greater than or equal to half of 5, round up to the next 5%
let rounded_value = if remainder >= 2 {
multiplied_value + (5 - remainder)
} else {
multiplied_value - remainder
};
// Divide by 100 to get back to a float
rounded_value / 100
}

View File

@@ -1,6 +1,14 @@
<html> <html>
<body> <body>
<input type="button" id="test" value="Test">
<h2>Current Firmware</h2>
<div>
<div id="firmware_buildtime">Buildtime loading</div>
<div id="firmware_githash">Build githash loading</div>
</div>
<h2>firmeware OTA v3</h2> <h2>firmeware OTA v3</h2>
<form id="upload_form" method="post"> <form id="upload_form" method="post">
<input type="file" name="file1" id="file1"><br> <input type="file" name="file1" id="file1"><br>
<progress id="progressBar" value="0" max="100" style="width:300px;"></progress> <progress id="progressBar" value="0" max="100" style="width:300px;"></progress>
@@ -9,6 +17,8 @@
<p id="loaded_n_total"></p> <p id="loaded_n_total"></p>
</form> </form>
<h2>config</h2> <h2>config</h2>
<div id="configform"> <div id="configform">
@@ -82,4 +92,4 @@
<script src="bundle.js"></script> <script src="bundle.js"></script>
</body> </body>
</html> </html>

View File

@@ -1,7 +1,11 @@
<html> <html>
<body> <body>
<input type="button" id="test" value="Test"> <input type="button" id="test" value="Test">
<h2>Current Firmware</h2>
<div>
<div id="firmware_buildtime">Buildtime loading</div>
<div id="firmware_githash">Build githash loading</div>
</div>
<div> <div>
<h2>firmeware OTA v3</h2> <h2>firmeware OTA v3</h2>
<form id="upload_form" method="post"> <form id="upload_form" method="post">

View File

@@ -10,7 +10,7 @@ use core::result::Result::Ok;
use embedded_svc::http::Method; use embedded_svc::http::Method;
use esp_idf_svc::http::server::{Configuration, EspHttpServer}; use esp_idf_svc::http::server::{Configuration, EspHttpServer};
use heapless::String; use heapless::String;
use serde::Serialize; use serde::{Deserialize, Serialize};
use crate::{ use crate::{
config::{Config, WifiConfig}, config::{Config, WifiConfig},
@@ -22,6 +22,17 @@ struct SSIDList<'a> {
ssids: Vec<&'a String<32>>, ssids: Vec<&'a String<32>>,
} }
#[derive(Serialize, Debug)]
struct VersionInfo<'a> {
git_hash: &'a str,
build_time: &'a str
}
#[derive(Serialize, Deserialize, Clone, Debug, PartialEq)]
pub struct TestPump{
pump: usize
}
pub fn httpd_initial(reboot_now: Arc<AtomicBool>) -> Box<EspHttpServer<'static>> { pub fn httpd_initial(reboot_now: Arc<AtomicBool>) -> Box<EspHttpServer<'static>> {
let mut server = shared(); let mut server = shared();
server server
@@ -85,15 +96,6 @@ pub fn httpd_initial(reboot_now: Arc<AtomicBool>) -> Box<EspHttpServer<'static>>
anyhow::Ok(()) anyhow::Ok(())
}) })
.unwrap(); .unwrap();
server
.fn_handler("/boardtest", Method::Post, move |_| {
let mut board = BOARD_ACCESS.lock().unwrap();
board.test()?;
anyhow::Ok(())
})
.unwrap();
server server
} }
@@ -170,7 +172,14 @@ pub fn shared() -> Box<EspHttpServer<'static>> {
server server
.fn_handler("/version", Method::Get, |request| { .fn_handler("/version", Method::Get, |request| {
let mut response = request.into_ok_response()?; let mut response = request.into_ok_response()?;
response.write(env!("VERGEN_GIT_DESCRIBE").as_bytes())?; let git_hash = env!("VERGEN_GIT_DESCRIBE");
let build_time = env!("VERGEN_BUILD_TIMESTAMP");
let version_info = VersionInfo{
git_hash,
build_time,
};
let version_info_json = serde_json::to_string(&version_info)?;
response.write(version_info_json.as_bytes())?;
anyhow::Ok(()) anyhow::Ok(())
}) })
.unwrap(); .unwrap();
@@ -244,4 +253,39 @@ pub fn shared() -> Box<EspHttpServer<'static>> {
}) })
.unwrap(); .unwrap();
server server
.fn_handler("/boardtest", Method::Post, move |_| {
let mut board = BOARD_ACCESS.lock().unwrap();
board.test()?;
anyhow::Ok(())
})
.unwrap();
server
.fn_handler("/pumptest", Method::Post, |mut request| {
let mut buf = [0_u8; 3072];
let read = request.read(&mut buf);
if read.is_err() {
let error_text = read.unwrap_err().to_string();
println!("Could not parse testrequest {}", error_text);
request
.into_status_response(500)?
.write(error_text.as_bytes())?;
return anyhow::Ok(());
}
let actual_data = &buf[0..read.unwrap()];
println!("Raw data {}", from_utf8(actual_data).unwrap());
let pump_test: Result<TestPump, serde_json::Error> = serde_json::from_slice(actual_data);
if pump_test.is_err() {
let error_text = pump_test.unwrap_err().to_string();
println!("Could not parse TestPump {}", error_text);
request
.into_status_response(500)?
.write(error_text.as_bytes())?;
return Ok(());
}
let mut board = BOARD_ACCESS.lock().unwrap();
board.test_pump(pump_test.unwrap().pump)?;
anyhow::Ok(())
})
.unwrap();
server
} }

View File

@@ -24,6 +24,10 @@ interface PlantConfig {
}[] }[]
} }
interface TestPump{
pump: number
}
let plants = document.getElementById("plants") as HTMLInputElement; let plants = document.getElementById("plants") as HTMLInputElement;
let fromWrapper = (() => { let fromWrapper = (() => {
@@ -77,9 +81,33 @@ let fromWrapper = (() => {
header.textContent = "Plant " + (i + 1); header.textContent = "Plant " + (i + 1);
plant.appendChild(header); plant.appendChild(header);
{ {
let holder = document.createElement("div"); let holder = document.createElement("div");
plant.appendChild(holder); plant.appendChild(holder);
let testButton = document.createElement("button");
testButton.innerText = "Test";
testButton.id = "plant_" + i + "_test";
testButton.onclick = function (){
var body:TestPump = {
pump: i
}
var pretty = JSON.stringify(body, undefined, 1);
fetch("/pumptest", {
method :"POST",
body: pretty
})
.then(response => response.text())
.then(text => submit_status.innerText = text)
};
holder.appendChild(testButton);
let br = document.createElement("br");
holder.appendChild(br);
let inputf = document.createElement("select"); let inputf = document.createElement("select");
inputf.id = "plant_" + i + "_mode"; inputf.id = "plant_" + i + "_mode";
inputf.onchange = updateJson; inputf.onchange = updateJson;

View File

@@ -33,5 +33,23 @@ export function uploadFile() {
ajax.send(file); ajax.send(file);
} }
interface VersionInfo{
git_hash:string,
build_time: string
}
let file1Upload = document.getElementById("file1") as HTMLInputElement; let file1Upload = document.getElementById("file1") as HTMLInputElement;
file1Upload.onchange = uploadFile; file1Upload.onchange = uploadFile;
let firmware_buildtime = document.getElementById("firmware_buildtime") as HTMLDivElement;
let firmware_githash = document.getElementById("firmware_githash") as HTMLDivElement;
document.addEventListener('DOMContentLoaded', function() {
fetch("/version")
.then(response => response.json())
.then(json => json as VersionInfo)
.then(versionInfo => {
firmware_buildtime.innerText = versionInfo.build_time;
firmware_githash.innerText = versionInfo.git_hash;
})
}, false);