Initial rough-in of motor controller

This commit is contained in:
2024-08-17 15:10:06 -04:00
parent 3633f636c6
commit 3185746213
11 changed files with 653 additions and 62 deletions

View File

@ -28,7 +28,7 @@ experimental = ["esp-idf-svc/experimental"]
embassy = ["esp-idf-svc/embassy-sync", "esp-idf-svc/critical-section", "esp-idf-svc/embassy-time-driver"]
[dependencies]
log = { version = "0.4", default-features = false }
log = { version = "0.4", default-features = false, features = ["max_level_trace"] }
esp-idf-svc = { version = "0.49", default-features = false }
esp32-nimble = "0.7.0"
esp-idf-hal = "0.44.1"
@ -38,6 +38,10 @@ embedded-io = "0.6.1"
anyhow = "1.0.86"
futures-lite = "2.3.0"
async-executor = "1.13.0"
async-channel = "2.3.1"
strum = "0.26.3"
strum_macros = "0.26.4"
async-io = "2.3.4"
[build-dependencies]
embuild = "0.32.0"

View File

@ -21,3 +21,12 @@ CONFIG_BT_NIMBLE_ENABLED=y
# Store BLE info in NVS
CONFIG_BT_NIMBLE_NVS_PERSIST=y
# Allow more levels of logs
# To change the levels of our crate, use the values in cargo.toml
# Change this to set log levels for the esp_idf; but unfortunately also the maximum for cargo.toml.
# Changing maximum level does not seem to accomplish anything despite this commit https://github.com/esp-rs/esp-idf-svc/commit/c76720402b3dc32cc42aec7c2feb4539cc7d2af9
# The unfortunate side effect of this is a 2k larger binary and log spam on startup.
# TODO: revisit and remove this for release?
CONFIG_LOG_DEFAULT_LEVEL_VERBOSE=y
CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE=y

View File

@ -3,15 +3,10 @@
// Example for reference; not ready to use at all.
use esp32_nimble::{enums::*, uuid128, BLEAdvertisementData, BLEDevice, NimbleProperties};
use esp_idf_hal::delay::FreeRtos;
use esp_idf_sys as _;
fn main() {
esp_idf_sys::link_patches();
// Bind the log crate to the ESP Logging facilities
esp_idf_svc::log::EspLogger::initialize_default();
use esp_idf_svc::timer::EspTaskTimerService;
use core::time::Duration;
fn run_ble_server() {
// Take ownership of device
let ble_device = BLEDevice::take();
@ -74,9 +69,12 @@ fn main() {
// Init a value to pass to characteristic
let mut val = 0;
let timer_service = EspTaskTimerService::new()?;
let mut async_timer = timer_service.timer_async()?;
loop {
FreeRtos::delay_ms(1000);
async_timer.after(Duration::from_secs(1)).await?;
my_service_characteristic.lock().set_value(&[val]).notify();
val = val.wrapping_add(1);
}

View File

@ -0,0 +1,35 @@
/// An enum of all commands passed into and out of the microcontroller
use strum_macros::EnumCount as EnumCountMacro;
use std::mem::discriminant;
#[derive(Clone, Copy, EnumCountMacro, Debug)]
pub enum Commands {
// Inputs sent from the PIC microcontroller
PicRecvUp,
PicRecvDown,
PicRecvStop,
// Inputs from bluetooth
BluetoothUp {data: u8},
BluetoothDown {data: u8},
BluetoothStop {_data: u8}, // There is no state where releasing the stop button induces a change.
// Internal messages
StopTimerExpired, // Sent when the 2 second stop sequence is complete
StopTimerRestart,
StopTimerClear,
ButtonTimerExpired,
ButtonTimerRestart,
ButtonTimerClear,
}
pub type CmdType = std::mem::Discriminant<Commands>;
/// Consider commands equal if they have the same command type, but different values
impl PartialEq for Commands {
fn eq(&self, other: &Self) -> bool {
discriminant(self) == discriminant(other)
}
}

View File

@ -0,0 +1,78 @@
use std::mem::discriminant;
use std::collections::HashMap;
use std::vec::Vec;
use async_channel::{unbounded, Receiver, Sender};
use strum::EnumCount;
use crate::commands::{Commands, CmdType};
use log::*; //{trace, debug, info, warn, error}
pub type SendQ = Sender<Commands>;
pub type RecvQ = Receiver<Commands>;
//TODO: Making this generic over a <C> for commands would make it a useful small event handler.
pub struct Dispatch {
callbacks: HashMap<CmdType, Vec<SendQ> >,
recv: RecvQ, // Channel to listen to incomming commands
endpoint: SendQ, // Endpoint to clone to hand to other modules, so that they can send commands
}
impl Dispatch {
pub fn new() -> Dispatch {
let (s, r) = unbounded();
let mut hmap = HashMap::new();
hmap.reserve(Commands::COUNT);
Dispatch { callbacks: hmap, recv: r, endpoint: s}
}
/// Get a channel receiver that will get callbacks for all commands in the listen_for vec.
pub fn get_callback_channel(&mut self, listen_for: &Vec<Commands>) -> RecvQ {
let (send, rec) = unbounded();
for cmd in listen_for {
let callback_list = self.callbacks.get_mut(&discriminant(&cmd));
match callback_list {
Some(callback) => {
callback.push(send.clone());
trace!("Adding {:?} to callbacks", cmd);
}
None => {
let mut callback = Vec::new();
callback.push(send.clone());
self.callbacks.insert(discriminant(&cmd), callback);
trace!("Created {:?} callback", cmd);
}
}
}
rec
}
//TODO: Make a discriminant version of this function that takes a vec of discriminants
//TODO: Most of these channels could be fixed size instead unbound; probably only the incomming channel needs to be large.
/// Get a channel sender that will send commands to this dispatcher
pub fn get_cmd_channel(&mut self) -> SendQ {
self.endpoint.clone()
}
/// Wait on incomming commands and dispatch them
pub async fn cmd_loop(&self) -> anyhow::Result<()> {
loop {
debug!("Dispatch waiting on commands");
let cmd = self.recv.recv().await?;
debug!("Dispatch got command {:?}", cmd);
let cmd_type = discriminant(&cmd);
let found_listeners = self.callbacks.get(&cmd_type);
match found_listeners {
Some(listeners) => {
for listener in listeners {
trace!("Sending cmd {:?}", cmd);
listener.send(cmd.clone()).await?;
}
}
None => {debug!("Dispatch found no listeners for a command")}
}
}
}
}

View File

@ -1,47 +1,99 @@
//use esp_idf_hal::peripherals::Peripherals;
const BUTTON_HOLD_TIME_MS: u64 = 500;
const STOP_SAFETY_TIME_MS: u64 = 2000;
use esp_idf_svc::timer::EspTaskTimerService;
use core::time::Duration;
use log::{info, error};
// Debug crates
//use esp_idf_svc::timer::EspTaskTimerService;
//use core::time::Duration;
// Crates used in release
use log::*; //{trace, debug, info, warn, error}
use anyhow::Result;
use async_executor::Executor;
use futures_lite::future;
use std::boxed::Box;
// Debug modules
mod test_console;
//mod test_driver_tattle;
// Release modules
mod commands;
mod dispatch;
mod motor_controller;
mod motor_driver;
mod message_timer;
use crate::message_timer::MessageTimer;
use crate::commands::Commands;
//TODO: limit switch driver, would be good in long run if it checked limit switches periodically (every 1s?) to ensure they are still functioning
fn main() {
// Do basic initialization
esp_idf_svc::sys::link_patches();
esp_idf_svc::log::EspLogger::initialize_default();
info!("Logging initialized");
//let peripherals = Peripherals::take().unwrap();
log::set_max_level(log::LevelFilter::Info);
match future::block_on(main_loop()) {
Ok(_) => {error!("Exited main loop normally, but this should be impossible.")}
Err(e) => {error!("Exited main loop with error {}", e)}
};
//TODO: can we restart the microcontroller here?
}
/*
async fn test_loop() -> Result<()> {
let timer_service = EspTaskTimerService::new()?;
let mut async_timer = timer_service.timer_async()?;
loop {
async_timer.after(Duration::from_secs(2)).await?;
async_timer.after(Duration::from_secs(5)).await?;
debug!("Tick ");
}
}
} */
async fn main_loop() -> Result<()> {
info!("Entering main loop");
// Create dispatch early so it can outlive most other things
let mut dp = dispatch::Dispatch::new();
// Debug Drivers
let motor_driver = Box::new(motor_driver::MotorDriverDebug {});
// Setup of various drivers that need to out-live the executor
let m_chan = motor_controller::Controller::prepare_controller(&mut dp);
let mut motor_control = motor_controller::Controller::new(m_chan, dp.get_cmd_channel(), motor_driver);
// Setup callback timers
let mut button_timer = MessageTimer::<Commands, Commands>::new_on_dispatch(
Commands::ButtonTimerRestart,
Commands::ButtonTimerClear,
Commands::ButtonTimerExpired,
BUTTON_HOLD_TIME_MS,
&mut dp);
let mut stopping_timer = MessageTimer::<Commands, Commands>::new_on_dispatch(
Commands::StopTimerRestart,
Commands::StopTimerClear,
Commands::StopTimerExpired,
STOP_SAFETY_TIME_MS,
&mut dp);
let executor = Executor::new();
let mut tasks:Vec<_> = Vec::new();
//Queueu up our async tasks
tasks.push(executor.spawn(test_console::start_cli()));
tasks.push(executor.spawn(test_loop()));
//Queue Up debug tasks (TODO: remove)
let cli_endpoint = dp.get_cmd_channel();
tasks.push(executor.spawn(test_console::start_cli(cli_endpoint)));
//tasks.push(executor.spawn(test_loop()));
//let t_chan = test_driver_tattle::prepare_tattle(&mut dp).expect("Failed to set up debugging copycat driver");
//tasks.push(executor.spawn(test_driver_tattle::start_tattle(t_chan)));
// Queueu up our async tasks
tasks.push(executor.spawn(motor_control.run()));
tasks.push(executor.spawn(button_timer.run()));
tasks.push(executor.spawn(stopping_timer.run()));
tasks.push(executor.spawn(dp.cmd_loop()));
//Once we have all our tasks, await on them all to run them in parallel.
for task in tasks {

View File

@ -0,0 +1,120 @@
use log::*; //{trace, debug, info, warn, error}
use anyhow::Result;
use esp_idf_svc::timer::{EspTaskTimerService, EspAsyncTimer};
use core::time::Duration;
use async_channel::{Receiver, Sender};
use futures_lite::FutureExt;
use crate::dispatch::Dispatch;
use crate::commands::Commands;
#[derive(Copy, Clone)]
enum State {
Running,
Stopped,
}
/// A timer that can be reset or canceled via message queue
/// Q is the type of enum on the receive Q, S on the send.
pub struct MessageTimer <Q, S> {
restart: Q,
cancel: Q,
done: S, // Send this when the timeout is hit
duration: Duration,
send_q: Sender<S>,
recv_q: Receiver<Q>,
state: State,
}
impl<Q: PartialEq, S: Copy> MessageTimer<Q, S> {
pub fn new(
restart: Q,
cancel: Q,
done: S,
duration:Duration,
send_q: Sender<S>,
recv_q: Receiver<Q>
) -> MessageTimer<Q, S> {
MessageTimer {
restart: restart,
cancel: cancel,
done: done,
duration: duration,
send_q: send_q,
recv_q: recv_q,
state: State::Stopped,
}
}
pub fn new_on_dispatch(
restart: Commands,
cancel: Commands,
done: Commands,
ms: u64,
dp: &mut Dispatch,
) -> MessageTimer<Commands, Commands> {
let cmds = vec![restart, cancel];
let s = dp.get_cmd_channel();
let r = dp.get_callback_channel(&cmds);
let duration = Duration::from_millis(ms);
MessageTimer {
restart:restart,
cancel: cancel,
done: done,
duration: duration,
send_q: s,
recv_q: r,
state: State::Stopped,
}
}
async fn wait_for_cmd(&self) -> Result<Q> {
Ok(self.recv_q.recv().await.unwrap())
}
async fn wait_with_timeout(&self, timer: &mut EspAsyncTimer) -> Result<Q> {
self.wait_for_cmd().or(async{
timer.after(self.duration).await?;
Err(anyhow::Error::from(std::io::Error::new(std::io::ErrorKind::TimedOut, "Timeout")))
}).await
}
async fn handle_cmd(&mut self, cmd: Result<Q>) {
match cmd {
Ok(msg) => {
if msg == self.restart {
self.state = State::Running; // timer will automatically reset
}
else if msg == self.cancel {
self.state = State::Stopped;
}
else {
warn!("Spurious messages have reset a timer!");
}
}
Err(_) => {
trace!("Timeout reached");
self.send_q.send(self.done).await.expect("Failed to send timeout");
}
}
}
pub async fn run(&mut self) -> Result<()> {
let mut cmd;
let timer_service = EspTaskTimerService::new()?;
let mut async_timer = timer_service.timer_async()?;
loop {
match self.state {
State::Running => {
cmd = self.wait_with_timeout(&mut async_timer).await;
}
State::Stopped => {
cmd = self.wait_for_cmd().await;
}
}
self.handle_cmd(cmd).await;
}
}
}

View File

@ -0,0 +1,192 @@
/// State machine of the motor's current state, that takes as inputs
/// command messages.
use log::*; //{trace, debug, info, warn, error}
//use async_channel::Receiver;
use anyhow::Result;
use std::boxed::Box;
use crate::commands::Commands;
use crate::motor_driver::MotorDriver;
use crate::dispatch::{Dispatch, RecvQ, SendQ};
#[derive(Debug, PartialEq, Clone)]
enum ControllerStates {
Stopped,
Stopping,
GoingUp,
GoingDown,
//TODO: AutoUp and AutoDown
}
pub struct Controller {
state: ControllerStates,
recv: RecvQ,
send: SendQ,
driver: Box<dyn MotorDriver>,
}
impl Controller {
pub fn new(recv: RecvQ, send: SendQ, driver: Box<dyn MotorDriver>) -> Controller {
Controller {
state: ControllerStates::Stopping,
recv: recv,
send: send,
driver: driver}
}
/// Tell the message dispatch which messages we are interested in receiving, and get
/// a callback channel that receives those messages.
pub fn prepare_controller(dp: &mut Dispatch) -> RecvQ {
let cmds = vec![
Commands::PicRecvUp,
Commands::PicRecvDown,
Commands::PicRecvStop,
Commands::BluetoothUp{data: 0},
Commands::BluetoothDown{data: 0},
Commands::BluetoothStop{_data: 0},
Commands::StopTimerExpired,
Commands::ButtonTimerExpired,
];
dp.get_callback_channel(&cmds)
}
async fn enter_state(&mut self, new_s: &ControllerStates) -> Result<()> {
match new_s {
ControllerStates::Stopped => {}
ControllerStates::Stopping => {
self.send.send(Commands::StopTimerRestart).await?;
self.driver.stop()?;
}
ControllerStates::GoingUp => {
self.send.send(Commands::ButtonTimerRestart).await?;
self.driver.start_up()?;
}
ControllerStates::GoingDown => {
self.send.send(Commands::ButtonTimerRestart).await?;
self.driver.start_down()?;
}
}
Ok(())
}
/// Maintain the current state - e.g. reset button timers, etc.
async fn maintain_state(&mut self) -> Result<()> {
match self.state {
ControllerStates::Stopped => {}
ControllerStates::Stopping => {} // Do not reset this timer; let it expire.
ControllerStates::GoingUp => {self.send.send(Commands::ButtonTimerRestart).await?;}
ControllerStates::GoingDown => {self.send.send(Commands::ButtonTimerRestart).await?;}
}
Ok(())
}
async fn exit_state(&mut self, old_s: &ControllerStates) -> Result <()> {
match old_s {
ControllerStates::Stopped => {}
ControllerStates::Stopping => {
self.send.send(Commands::StopTimerClear).await?;
}
ControllerStates::GoingUp => {
self.send.send(Commands::ButtonTimerClear).await?;
}
ControllerStates::GoingDown => {
self.send.send(Commands::ButtonTimerClear).await?;
}
}
Ok(())
}
/// Determines the state the controller should be in based on the command received.
fn handle_cmd(&mut self, cmd: &Commands) -> ControllerStates {
match self.state {
ControllerStates::Stopped => {
match cmd {
Commands::PicRecvUp => {return ControllerStates::GoingUp}
Commands::PicRecvDown => {return ControllerStates::GoingDown}
Commands::BluetoothUp { data } => {
match data {
0 => {}
1 => {return ControllerStates::GoingUp}
_ => {error!("Invalid data sent via BluetoothUp: {}", data); return ControllerStates::Stopping}
}
}
Commands::BluetoothDown { data } => {
match data {
0 => {}
1 => {return ControllerStates::GoingDown}
_ => {error!("Invalid data sent via BluetoothDown: {}", data); return ControllerStates::Stopping}
}
}
_ => {} // Ignore other commands when stopped.
}
}
ControllerStates::Stopping => {
match cmd {
Commands::StopTimerExpired => {return ControllerStates::Stopped}
_ => {} // Ignore other commands when stopping
}
}
ControllerStates::GoingUp => {
match cmd {
Commands::PicRecvUp => {return self.state.clone()}
Commands::BluetoothUp { data } => {
match data {
0 => {} // Not an error, but transition to stop
1 => {return self.state.clone()}
_ => {error!("Invalid data sent via BluetoothUp: {}", data)}
}
}
_ => {} // fall through to GoingUp default of stopping
}
return ControllerStates::Stopping; // Almost every command will be interpreted as stop
}
ControllerStates::GoingDown => {
match cmd {
Commands::PicRecvDown => {return self.state.clone()}
Commands::BluetoothDown { data } => {
match data {
0 => {} // Not an error, but transition to stop
1 => {return self.state.clone()}
_ => {error!("Invalid data sent via BluetoothDown: {}", data)}
}
}
_ => {} // fall through to GoingDown default of stopping
}
return ControllerStates::Stopping
}
}
self.state.clone() //Don't transition states by default.
}
async fn transition_state(&mut self, old_s: &ControllerStates, new_s: &ControllerStates) -> Result<()> {
if old_s != new_s {
self.exit_state(&old_s).await?;
self.enter_state(&new_s).await?;
}
else {
self.maintain_state().await?;
}
self.state = new_s.clone();
Ok(())
}
pub async fn run(&mut self) -> Result<()> {
// On entry, assume initial stopping state
debug!("Setting motor controller initial state to stopping");
self.state = ControllerStates::Stopping;
self.enter_state(&ControllerStates::Stopping).await?;
loop {
let cmd = self.recv.recv().await?;
trace!("Got command {:?}",cmd);
let new_s = self.handle_cmd(&cmd);
trace!("State current {:?} new {:?}", self.state, new_s);
self.transition_state(&self.state.clone(), &new_s).await?
}
}
}

View File

@ -0,0 +1,29 @@
/// Handles the actual hardware interface with motor or its controller.
use log::*; //{trace, debug, info, warn, error}
use anyhow::Result;
pub trait MotorDriver: Send + Sync {
fn start_up(&mut self) -> Result<()>;
fn start_down(&mut self) -> Result<()>;
fn stop(&mut self) -> Result<()>;
}
pub struct MotorDriverDebug {}
impl MotorDriver for MotorDriverDebug {
fn start_up(&mut self) -> Result<()> {
warn!("Starting motor, direction: Up");
Ok(())
}
fn start_down(&mut self) -> Result<()> {
warn!("Starting motor, direction: Down");
Ok(())
}
fn stop(&mut self) ->Result<()> {
warn!("Stopping motor");
Ok(())
}
}
//unsafe impl Send for MotorDriverDebug {}

View File

@ -23,96 +23,95 @@ use ::{
//time::Duration, // could also use core::time::Duration?
},
core::time::Duration,
log::{info, warn},
};
use crate::commands::Commands;
use async_channel::Sender;
use log::*; //{trace, debug, info, warn, error}
#[derive(Command)]
pub enum Menu<'a> {
/// Send a button press: Up
ButtonUp,
/// Simulate the PIC controller sending aus n Up character
PicRecvUp,
/// Send a button press: Down
ButtonDown,
/// Simulate the PIC controller sending us a Down character
PicRecvDown,
/// Send a button press: Auto toggle on/off
ButtonAuto,
/// Send a button press: Pair/forget
ButtonPair,
/// Simulate the PIC controller sending us a Stop character
PicRecvStop,
/// Send a bluetooth characteristic: Up
BluetoothUp {
/// 0 for not pressed, 1 for pressed
data: u8,
},
/// Send a bluetooth characteristic: Down
BluetoothDown {
/// 0 for not pressed, 1 for pressed
data: u8,
},
/// Send a bluetooth characteristic: Stop
BluetoothStop {
/// 0 for not pressed, 1 for pressed
data: u8,
},
/// Send a bluetooth characteristic: Learn
BluetoothLearn {
/// 0 for not pressed, 1 for pressed
data: u8,
},
/// Send a bluetooth characteristic: Auto
BluetoothAuto {
/// 0 for not pressed, 1 for pressed
data: u8,
},
/// Send a bluetooth characteristic: Limits
BluetoothTopLimit { data: u8 },
/// Send a bluetooth characteristic: Limits
BluetoothBottomLimit { data: u8 },
/// Send a bluetooth characteristic: Wifi SSID
BluetoothWifiSsid { ssid: &'a str },
/// Send a bluetooth characteristic: Wifi Password
BluetoothWifiPassword { wifipass: &'a str },
Log { level: u8 },
}
pub fn process_menu(
cli: &mut CliHandle<'_, SimpleWriter, Infallible>,
command: Menu<'_>,
dispatch: &Sender<Commands>,
) -> Result<(), Infallible> {
match command {
Menu::ButtonUp => {
cli.writer().write_str("TODO: simulate button")?;
// We ignore sending errors throughout because the Cli interface is only for
// testing and debugging.
Menu::PicRecvUp => {
cli.writer().write_str("Sending PicButtonUp Received command")?;
let _ = dispatch.send_blocking(Commands::PicRecvUp);
}
Menu::ButtonDown => {
cli.writer().write_str("TODO: simulate button")?;
Menu::PicRecvDown => {
cli.writer().write_str("Sending PicButtonDown command")?;
let _ = dispatch.send_blocking(Commands::PicRecvDown);
}
Menu::ButtonAuto => {
cli.writer().write_str("TODO: simulate button")?;
}
Menu::ButtonPair => {
cli.writer().write_str("TODO: simulate button")?;
Menu::PicRecvStop => {
cli.writer().write_str("Sending PicButtonStop command")?;
let _ = dispatch.send_blocking(Commands::PicRecvStop);
}
Menu::BluetoothUp { data } => {
cli.writer()
.write_str("TODO: simulate bluetooth characteristic change")?;
let _ = data;
.write_str("Sending BluetoothUp")?;
let _ = dispatch.send_blocking(Commands::BluetoothUp { data: data });
}
Menu::BluetoothDown { data } => {
cli.writer()
.write_str("TODO: simulate bluetooth characteristic change")?;
let _ = data;
.write_str("Sending BluetoothDown")?;
let _ = dispatch.send_blocking(Commands::BluetoothDown { data: data });
}
Menu::BluetoothStop { data } => {
cli.writer()
.write_str("TODO: simulate bluetooth characteristic change")?;
let _ = data;
.write_str("SendingBluetoothStop")?;
let _ = dispatch.send_blocking(Commands::BluetoothStop { _data: data });
}
Menu::BluetoothLearn { data } => {
cli.writer()
@ -144,6 +143,39 @@ pub fn process_menu(
.write_str("TODO: simulate bluetooth characteristic change {}")?;
let _ = wifipass;
}
Menu::Log { level } => {
match level {
0 => {
cli.writer().write_str("Log set to Off")?;
log::set_max_level(log::LevelFilter::Off);
}
1 => {
cli.writer().write_str("Log set to Error")?;
log::set_max_level(log::LevelFilter::Error);
}
2 => {
cli.writer().write_str("Log set to Warn")?;
log::set_max_level(log::LevelFilter::Warn);
}
3 => {
cli.writer().write_str("Log set to Info")?;
log::set_max_level(log::LevelFilter::Info);
}
4 => {
cli.writer().write_str("Log set to Debug")?;
log::set_max_level(log::LevelFilter::Debug);
}
_ => {
cli.writer().write_str("Log set to Trace")?;
log::set_max_level(log::LevelFilter::Trace);
}
}
error!("error test");
warn!("warn test");
info!("info test");
debug!("debug test");
trace!("trace test");
}
}
Ok(())
}
@ -157,19 +189,19 @@ impl embedded_io::ErrorType for SimpleWriter {
impl embedded_io::Write for SimpleWriter {
fn write(&mut self, buf: &[u8]) -> Result<usize, Self::Error> {
stdout().write(&buf).unwrap(); //TODO: handle errors?
stdout().write(&buf).unwrap();
Ok(buf.len())
}
fn flush(&mut self) -> Result<(), Self::Error> {
let _ = stdout().flush(); //TODO currently ignoring this error
let _ = stdout().flush();
Ok(())
}
}
pub async fn start_cli() -> anyhow::Result<()> {
let timer_service = EspTaskTimerService::new().unwrap(); //TODO: handle this error
info!("Setting up command line listern and processor");
pub async fn start_cli(dispatch: Sender<Commands>) -> anyhow::Result<()> {
let timer_service = EspTaskTimerService::new()?;
info!("Setting up command line listener and processor");
let writer = SimpleWriter {};
let mut cli = CliBuilder::default()
.writer(writer)
@ -184,7 +216,11 @@ pub async fn start_cli() -> anyhow::Result<()> {
async_timer.after(Duration::from_millis(SLEEP_TIME_MS)).await?;
match reader.read_exact(&mut buf) {
Ok(_) => {
cli.process_byte::<Menu, _>(buf[0], &mut Menu::processor(process_menu))?;
//cli.process_byte::<Menu, _>(buf[0], &mut Menu::processor(process_menu))?;
cli.process_byte::<Menu, _>(buf[0], &mut Menu::processor(
|cli, command| {
process_menu(cli, command, &dispatch)
}))?;
}
Err(e) => match e.kind() {
std::io::ErrorKind::WouldBlock => {} // This is expected if there is no input

View File

@ -0,0 +1,38 @@
/// Listen to every command handled by dispatch, and report it to uart.
use log::*; //{trace, debug, info, warn, error}
use strum::EnumCount;
use crate::commands::Commands;
use crate::dispatch::Dispatch;
use async_channel::Receiver;
pub fn prepare_tattle(dispatch: &mut Dispatch) -> anyhow::Result<Receiver<Commands>> {
let cmds = vec![
Commands::PicRecvUp,
Commands::PicRecvDown,
Commands::PicRecvStop,
Commands::BluetoothUp{data: 0},
Commands::BluetoothDown{data: 0},
Commands::BluetoothStop{_data: 0},
Commands::StopTimerExpired,
Commands::StopTimerRestart,
Commands::StopTimerClear,
Commands::ButtonTimerExpired,
Commands::ButtonTimerRestart,
Commands::ButtonTimerClear,
];
if Commands::COUNT != cmds.len() {
warn!("Incorrect number of commands are being tattled on. Total commands: {}, listening to {}", Commands::COUNT, cmds.len());
}
let r_channel = dispatch.get_callback_channel(&cmds);
Ok(r_channel)
}
pub async fn start_tattle(r_channel: Receiver<Commands>) -> anyhow::Result<()> {
debug!("Tattle started listening to messages");
loop {
let msg = r_channel.recv().await?;
debug!("Message: {:?}", msg);
}
}