first commit

This commit is contained in:
aOK 2024-01-02 19:37:23 +03:00
commit 4dceb5b597
14 changed files with 1879 additions and 0 deletions

13
.cargo/config.toml Normal file
View File

@ -0,0 +1,13 @@
[target.'cfg(all(target_arch = "arm", target_os = "none"))']
# replace STM32F429ZITx with your chip as listed in `probe-rs chip list`
runner = "probe-rs run --chip STM32F429ZITx --speed 10000000"
[build]
target = "thumbv7em-none-eabi"
[env]
DEFMT_LOG = "trace"
[unstable]
build-std = ["alloc", "core"]

1
.gitignore vendored Normal file
View File

@ -0,0 +1 @@
/target

1291
Cargo.lock generated Normal file

File diff suppressed because it is too large Load Diff

59
Cargo.toml Normal file
View File

@ -0,0 +1,59 @@
[package]
name = "stmspeedgovdevice"
version = "0.1.0"
edition = "2021"
# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
[dependencies]
# Change stm32f429zi to your chip name, if necessary.
embassy-stm32 = { version = "0.1.0", features = [ "defmt", "stm32f429zi", "unstable-pac", "memory-x", "time-driver-any", "exti", "chrono"] }
embassy-sync = { version = "0.5.0", features = ["defmt"] }
embassy-executor = { version = "0.4.0", features = ["arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
embassy-time = { version = "=0.2.*", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
embassy-usb = { version = "0.1.0", features = ["defmt" ] }
embassy-net = { version = "0.2", features = ["defmt", "tcp", "dhcpv4", "medium-ethernet", ] }
atat = { version="0.20.0", features = ["async", "log"] }
defmt = "0.3"
defmt-rtt = "0.4"
cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] }
cortex-m-rt = "0.7.0"
embedded-hal = "0.2.7"
embedded-alloc = "0.5.1"
critical-section = "1.1.2"
linked_list_allocator = "0.10.5"
embedded-hal-hal = { package = "embedded-hal", version = "1.0.0-rc.2"}
embedded-io = { version = "0.6.0" }
embedded-io-async = { version = "0.6.1" }
panic-probe = { version = "0.3", features = ["print-defmt"] }
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
heapless = { version = "0.8", default-features = false }
nb = "1.0.0"
embedded-storage = "0.3.1"
micromath = "2.0.0"
# static_cell = "2"
static_cell = { version = "2.0.0", features = ["nightly"] }
chrono = { version = "^0.4", default-features = false}
# simcom = { package = "simcom-gprs-driver", path = "../../exprojects/chip-drivers/cellular/simcom-gprs", features = [] }
simcom = { package = "simcom-gprs-driver",git = "https://github.com/rmja/chip-drivers.git", branch = "master", features = ["sim900"] }
[patch.crates-io]
# ublox-sockets = { git = "https://github.com/BlackbirdHQ/ublox-sockets", branch = "feature/async-borrowed-sockets" }
atat = { git = "https://github.com/BlackbirdHQ/atat", branch = "master" }
no-std-net = { git = "https://github.com/rushmorem/no-std-net", branch = "issue-15" }
embassy-stm32 = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-time = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-sync = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-futures = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-executor = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-usb = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
embassy-net = { git = "https://github.com/embassy-rs/embassy", branch = "main" }
[profile.release]
debug = 2

0
README.md Normal file
View File

5
build.rs Normal file
View File

@ -0,0 +1,5 @@
fn main() {
println!("cargo:rustc-link-arg-bins=--nmagic");
println!("cargo:rustc-link-arg-bins=-Tlink.x");
println!("cargo:rustc-link-arg-bins=-Tdefmt.x");
}

View File

@ -0,0 +1,13 @@
[toolchain]
channel = "1.75"
# channel = "1.74"
components = [ "rust-src", "rustfmt", "llvm-tools" ]
targets = [
"thumbv7em-none-eabi",
"thumbv7m-none-eabi",
"thumbv6m-none-eabi",
"thumbv7em-none-eabihf",
"thumbv8m.main-none-eabihf",
"riscv32imac-unknown-none-elf",
"wasm32-unknown-unknown",
]

15
rust-toolchain.toml Normal file
View File

@ -0,0 +1,15 @@
[toolchain]
channel = "nightly-2023-12-29"
# channel = "nightly-2023-12-20"
# 2023-12-29
# 2023-12-20
components = [ "rust-src", "rustfmt", "llvm-tools", "miri" ]
targets = [
"thumbv7em-none-eabi",
"thumbv7m-none-eabi",
"thumbv6m-none-eabi",
"thumbv7em-none-eabihf",
"thumbv8m.main-none-eabihf",
"riscv32imac-unknown-none-elf",
"wasm32-unknown-unknown",
]

34
src/common/general/mod.rs Normal file
View File

@ -0,0 +1,34 @@
//! ### 4 - General Commands
pub mod responses;
pub mod urc;
use atat::atat_derive::AtatCmd;
use responses::*;
/// 4.1 Manufacturer identification +CGMI
///
/// Text string identifying the manufacturer.
#[derive(Clone, AtatCmd)]
#[at_cmd("+CGMI", ManufacturerId)]
pub struct GetManufacturerId;
/// Model identification +CGMM
///
/// Read a text string that identifies the device model.
#[derive(Clone, AtatCmd)]
#[at_cmd("+CGMM", ModelId)]
pub struct GetModelId;
/// Software version identification +CGMR
///
/// Read a text string that identifies the software version of the module
#[derive(Clone, AtatCmd)]
#[at_cmd("+CGMR", SoftwareVersion)]
pub struct GetSoftwareVersion;
/// 7.12 Wi-Fi MAC address +UWAPMACADDR
///
/// Lists the currently used MAC address.
#[derive(Clone, AtatCmd)]
#[at_cmd("+UWAPMACADDR", WifiMac)]
pub struct GetWifiMac;

View File

@ -0,0 +1,30 @@
//! Responses for General Commands
use atat::atat_derive::AtatResp;
use atat::heapless::String;
/// 4.1 Manufacturer identification
/// Text string identifying the manufacturer.
#[derive(Clone, Debug, AtatResp)]
pub struct ManufacturerId {
pub id: String<64>,
}
/// Model identification
/// Text string identifying the manufacturer.
#[derive(Clone, Debug, AtatResp)]
pub struct ModelId {
pub id: String<64>,
}
/// Software version identification
/// Read a text string that identifies the software version of the module.
#[derive(Clone, Debug, AtatResp)]
pub struct SoftwareVersion {
pub id: String<64>,
}
/// 7.11 Wi-Fi Access point station list +UWAPSTALIST
#[derive(Clone, AtatResp)]
pub struct WifiMac {
pub mac_addr: atat::heapless_bytes::Bytes<12>,
}

View File

@ -0,0 +1,4 @@
use atat::atat_derive::AtatResp;
#[derive(Clone, AtatResp)]
pub struct MessageWaitingIndication;

18
src/common/mod.rs Normal file
View File

@ -0,0 +1,18 @@
pub mod general;
use atat::atat_derive::AtatUrc;
use atat::atat_derive::{AtatCmd, AtatResp};
#[derive(Clone, AtatResp)]
pub struct NoResponse;
#[derive(Clone, AtatCmd)]
#[at_cmd("", NoResponse, timeout_ms = 1000)]
pub struct AT;
#[derive(Clone, AtatUrc)]
pub enum Urc {
#[at_urc("+UMWI")]
MessageWaitingIndication(general::urc::MessageWaitingIndication),
}

87
src/lib.rs Normal file
View File

@ -0,0 +1,87 @@
#![no_std]
pub mod common;
use core::{
alloc::{GlobalAlloc, Layout},
cell::RefCell,
ptr::{self, NonNull},
};
use critical_section::Mutex;
use linked_list_allocator::Heap;
pub struct EspHeap {
heap: Mutex<RefCell<Heap>>,
}
impl EspHeap {
/// Crate a new UNINITIALIZED heap allocator
///
/// You must initialize this heap using the
/// [`init`](struct.EspHeap.html#method.init) method before using the
/// allocator.
pub const fn empty() -> EspHeap {
EspHeap {
heap: Mutex::new(RefCell::new(Heap::empty())),
}
}
/// Initializes the heap
///
/// This function must be called BEFORE you run any code that makes use of
/// the allocator.
///
/// `heap_bottom` is a pointer to the location of the bottom of the heap.
///
/// `size` is the size of the heap in bytes.
///
/// Note that:
///
/// - The heap grows "upwards", towards larger addresses. Thus `end_addr`
/// must be larger than `start_addr`
///
/// - The size of the heap is `(end_addr as usize) - (start_addr as usize)`.
/// The allocator won't use the byte at `end_addr`.
///
/// # Safety
///
/// Obey these or Bad Stuff will happen.
///
/// - This function must be called exactly ONCE.
/// - `size > 0`
pub unsafe fn init(&self, heap_bottom: *mut u8, size: usize) {
critical_section::with(|cs| self.heap.borrow(cs).borrow_mut().init(heap_bottom, size));
}
/// Returns an estimate of the amount of bytes in use.
pub fn used(&self) -> usize {
critical_section::with(|cs| self.heap.borrow(cs).borrow_mut().used())
}
/// Returns an estimate of the amount of bytes available.
pub fn free(&self) -> usize {
critical_section::with(|cs| self.heap.borrow(cs).borrow_mut().free())
}
}
unsafe impl GlobalAlloc for EspHeap {
unsafe fn alloc(&self, layout: Layout) -> *mut u8 {
critical_section::with(|cs| {
self.heap
.borrow(cs)
.borrow_mut()
.allocate_first_fit(layout)
.ok()
.map_or(ptr::null_mut(), |allocation| allocation.as_ptr())
})
}
unsafe fn dealloc(&self, ptr: *mut u8, layout: Layout) {
critical_section::with(|cs| {
self.heap
.borrow(cs)
.borrow_mut()
.deallocate(NonNull::new_unchecked(ptr), layout)
});
}
}

309
src/main.rs Normal file
View File

@ -0,0 +1,309 @@
#![no_std]
#![no_main]
#![allow(stable_features)]
#![feature(type_alias_impl_trait)]
extern crate alloc;
use atat::asynch::Client;
use atat::ResponseSlot;
use atat::UrcChannel;
use core::cell::RefCell;
use cortex_m_rt::entry;
use defmt::*;
use embassy_executor::{Executor, Spawner};
use embassy_stm32::gpio::{AnyPin, Input, Level, Output, OutputOpenDrain, Pin, Pull, Speed};
use embassy_stm32::peripherals::PD12;
use embassy_stm32::peripherals::USART3;
use embassy_stm32::time::Hertz;
use embassy_stm32::time::{khz, mhz};
use embassy_stm32::usart::UartTx;
use embassy_stm32::usart::{BufferedUart, BufferedUartRx, BufferedUartTx};
use embassy_stm32::{bind_interrupts, interrupt, peripherals, usart, Config};
use embassy_time::{Duration, Timer};
use static_cell::StaticCell;
use {defmt_rtt as _, panic_probe as _};
use atat::asynch::AtatClient;
use atat::{AtDigester, AtatIngress, DefaultDigester, Ingress, Parser};
use core::mem::MaybeUninit;
use simcom::{
services::network::NetworkError, DriverError, SimcomConfig, SimcomDevice, SimcomIngress,
SimcomResponseSlot, SimcomUrcChannel,
};
use stmspeedgovdevice::common;
use {defmt_rtt as _, panic_probe as _};
bind_interrupts!(struct Irqs {
USART3 => embassy_stm32::usart::BufferedInterruptHandler<peripherals::USART3>;
});
// bind_interrupts!(struct Irqs {
// USART3 => embassy_stm32::usart::BufferedInterruptHandler<USART3>;
// });
const INGRESS_BUF_SIZE: usize = 1024;
const URC_CAPACITY: usize = 2;
const URC_SUBSCRIBERS: usize = 2;
static EXECUTOR: StaticCell<Executor> = StaticCell::new();
#[global_allocator]
static ALLOCATOR: stmspeedgovdevice::EspHeap = stmspeedgovdevice::EspHeap::empty();
fn init_heap() {
const HEAP_SIZE: usize = 32 * 1024;
static mut HEAP: MaybeUninit<[u8; HEAP_SIZE]> = MaybeUninit::uninit();
unsafe {
ALLOCATOR.init(HEAP.as_mut_ptr() as *mut u8, HEAP_SIZE);
}
}
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
init_heap();
info!("Hello World!");
let executor = EXECUTOR.init(Executor::new());
executor.run(|spawner| {
unwrap!(spawner.spawn(test_uart_device_setup(spawner)));
})
// info!("Hello World!");
// let (ingress, devc, rx14) = test_uart_device_setup(p.PC10, p.PC11, p.USART3);
// spawner.spawn(ingress_task(ingress, reader)).unwrap();
// unwrap!(spawner.spawn(ingress_task(ingress, rx14)));
// unwrap!(spawner.spawn(testsetup(devc)));
}
// #[embassy_executor::task]
// async fn buf_u(mut buf_usart: BufferedUart<'static, embassy_stm32::peripherals::USART3>) {
// loop {
// let buf = buf_usart.fill_buf().await.unwrap();
// info!("Received: {}", buf);
// // Read bytes have to be explicitly consumed, otherwise fill_buf() will return them again
// let n = buf.len();
// buf_usart.consume(n);
// }
// }
// #[embassy_executor::task]
// pub async fn ingress_task(
// mut ingress: SimcomIngress<'static, INGRESS_BUF_SIZE>,
// mut rx: BufferedUartRx<'static, USART3>,
// ) {
// defmt::info!("reading in ingress_task...");
// ingress.read_from(&mut rx).await;
// }
#[embassy_executor::task(pool_size = 3)]
async fn blinky(mut led: AnyPin) {
let mut output = Output::new(led, Level::High, Speed::Low).degrade();
loop {
output.set_high();
Timer::after(Duration::from_millis(1000)).await;
output.set_low();
Timer::after(Duration::from_millis(1000)).await;
}
}
#[embassy_executor::task]
async fn led_blink(p: PD12) {
let mut led = Output::new(p, Level::High, Speed::Low);
loop {
info!("high");
led.set_high();
Timer::after(Duration::from_millis(300)).await;
info!("low");
led.set_low();
Timer::after(Duration::from_millis(300)).await;
}
}
// -> (
// // atat::asynch::Client<'static, UartTx<'static, hal::peripherals::UART1>, INGRESS_BUF_SIZE>,
// // SimcomDevice<'static, 'static, atat::asynch::Client<'static, UartTx<'static, UART1>, INGRESS_BUF_SIZE>
// SimcomIngress<'static, INGRESS_BUF_SIZE>,
// SimcomDevice<
// 'static,
// 'static,
// atat::asynch::Client<'static, UartTx<'static, UART1>, INGRESS_BUF_SIZE>,
// TestConfig,
// >,
// UartRx<'static, UART1>,
// )
#[embassy_executor::task]
pub async fn test_uart_device_setup(spawner: Spawner) {
let mut config = Config::default();
{
use embassy_stm32::rcc::*;
config.rcc.hse = Some(Hse {
freq: Hertz(8_000_000),
mode: HseMode::Bypass,
});
config.rcc.pll_src = PllSource::HSE;
config.rcc.pll = Some(Pll {
prediv: PllPreDiv::DIV4,
mul: PllMul::MUL180,
divp: Some(PllPDiv::DIV2), // 8mhz / 4 * 180 / 2 = 180Mhz.
divq: None,
divr: None,
});
config.rcc.ahb_pre = AHBPrescaler::DIV1;
config.rcc.apb1_pre = APBPrescaler::DIV4;
config.rcc.apb2_pre = APBPrescaler::DIV2;
config.rcc.sys = Sysclk::PLL1_P;
}
let p = embassy_stm32::init(config);
static tx_buf: StaticCell<[u8; 16]> = StaticCell::new();
static rx_buf: StaticCell<[u8; 16]> = StaticCell::new();
let (tx_pin, rx_pin, uart) = (p.PC10, p.PC11, p.USART3);
let mut uart_config = embassy_stm32::usart::Config::default();
{
uart_config.baudrate = 115200;
// uart_config.baudrate = 9600;
uart_config.parity = embassy_stm32::usart::Parity::ParityNone;
uart_config.stop_bits = embassy_stm32::usart::StopBits::STOP1;
uart_config.data_bits = embassy_stm32::usart::DataBits::DataBits8;
}
let uart = BufferedUart::new(
uart,
Irqs,
rx_pin,
tx_pin,
tx_buf.init([0u8; 16]),
rx_buf.init([0u8; 16]),
uart_config,
);
let (txPC10, rxPC11) = uart.unwrap().split();
// static BUFFERS: Buffers<modem::Urc, INGRESS_BUF_SIZE, URC_CAPACITY, URC_SUBSCRIBERS> =
// Buffers::<modem::Urc, INGRESS_BUF_SIZE, URC_CAPACITY, URC_SUBSCRIBERS>::new();
static RES_SLOT: SimcomResponseSlot<INGRESS_BUF_SIZE> = SimcomResponseSlot::new();
static URC_CHANNEL: SimcomUrcChannel = SimcomUrcChannel::new();
let ingress = SimcomIngress::new(&RES_SLOT, &URC_CHANNEL);
// static buf: StaticCell<[u8; INGRESS_BUF_SIZE]> = StaticCell::new();
let buf = static_cell::make_static!([0; 1024]);
let config = TestConfig(ResetPin(true));
let device = SimcomDevice::new(txPC10, &RES_SLOT, &URC_CHANNEL, buf, config);
// let mut client = Client::new(tx, &RES_SLOT, buf, atat::Config::default());
//
// (ingress, device, rx)
// unwrap!(spawner.spawn(ingress_task(ingress, rxPC11)));
// unwrap!(spawner.spawn(testsetup(device)));
unwrap!(spawner.spawn(led_blink(p.PD12)));
}
// #[embassy_executor::task]
// pub async fn testsetup(
// mut device: SimcomDevice<
// 'static,
// 'static,
// atat::asynch::Client<'static, BufferedUartTx<'static, USART3>, INGRESS_BUF_SIZE>,
// TestConfig,
// >,
// ) {
// // let m = device.handle;
// // let tcp = device.data("internet".into()).await.unwrap();
// match device.data("internet".into()).await {
// Ok(tcp) => {
// defmt::info!("{:?}", tcp.local_ip);
// }
// Err(e) => match e {
// DriverError::Atat(atat::Error::Timeout) => {
// defmt::error!("[DriverError - Timeout]: {:?}", e);
// }
// _ => {}
// },
// }
// // defmt::info!("{:?}", tcp.local_ip);
// // defmt::info!("Logger is setup");
// // match device.network().attach(None).await {
// // Ok(d) => {
// // defmt::info!("network().attach Sent: {:?}", d)
// // }
// // Err(e) => match e {
// // NetworkError::Atat(atat::Error::Timeout) => {
// // defmt::error!("[network().attach] - Timeout Error: {:?}", e)
// // }
// // _ => {}
// // },
// // }
// // match device.reset().await {
// // Ok(d) => {
// // defmt::info!("device.reset() Sent: {:?}", d)
// // }
// // Err(e) => match e {
// // DriverError::Atat(atat::Error::Timeout) => {
// // defmt::error!("[device.reset()] - Timeout Error: {:?}", e)
// // }
// // _ => {}
// // },
// // }
// // match device.setup().await {
// // Ok(d) => {
// // defmt::info!("device.setup() Sent: {:?}", d)
// // }
// // Err(e) => match e {
// // DriverError::Atat(atat::Error::Timeout) => {
// // defmt::error!("[device.setup()] - Timeout Error: {:?}", e)
// // }
// // DriverError::BaudDetection => {
// // defmt::error!("[device.setup()] - BaudDetection Error: {:?}", e)
// // }
// // _ => {}
// // },
// // }
// // let mut network = device.network();
// // network.attach(None).await.unwrap();
// }
use core::convert::Infallible;
use embedded_hal_hal::digital::{ErrorType, OutputPin};
// use embedded_hal::digital::v2::OutputPin;
// use embedded_nal_async::{IpAddr, Ipv4Addr, SocketAddr};
pub struct TestConfig(ResetPin);
pub struct ResetPin(bool);
impl SimcomConfig for TestConfig {
type ResetPin = ResetPin;
fn reset_pin(&mut self) -> &mut Self::ResetPin {
&mut self.0
}
}
impl OutputPin for ResetPin {
fn set_low(&mut self) -> Result<(), Self::Error> {
self.0 = false;
Ok(())
}
fn set_high(&mut self) -> Result<(), Self::Error> {
self.0 = true;
Ok(())
}
}
impl ErrorType for ResetPin {
type Error = Infallible;
}