Skip to content
Snippets Groups Projects
Commit d8a002ea authored by Joakim Lundberg's avatar Joakim Lundberg
Browse files

removed old files from wrong repo.

parent 38079b77
No related branches found
No related tags found
No related merge requests found
use f4::Serial;
use f4::serial::Usart;
use core::any::Any;
/// Timeout for the connection to ESP-Link
pub const ESP_TIMEOUT: u32 = 2000;
/// Codes used by slip
#[derive(PartialEq, Eq)] // Fler
pub enum SlipCodes {
SlipEnd = 0xC0, // OCT: 0300
SlipEsc = 0xDB, // OCT: 0333
SlipEscEnd = 0xDC, // OCT: 0334
SlipEscEsc = 0xDE, // OCT: 0335
}
/// Commands for the ESP-Link device
#[derive(PartialEq, Eq)]
pub enum Commands {
Null = 0,
Sync,
ResponseValue,
ResponseCallback,
WiFiStatus,
CallbackAdd,
CallbackEvents,
GetTime,
// MQTT
MQTTSetup = 10,
MQTTPublish,
MQTTSubscribe,
MQTTLWT,
// REST
RESTSetup = 20,
RESTRequest,
RESTSetHeader,
// Webserver
WEBSetup = 30,
WEBData,
// Socket connection
SOCKETSetup = 40,
SOCKETSend,
}
/// WiFi status given by ESP-Link
#[derive(PartialEq, Eq)]
pub enum WIFIStatus {
STATIONIdle = 0,
STATIONConnecting,
STATIONWrongPassword,
STATIONNoAPFound,
STATIONConnectFail,
STATIONGotIP,
}
/// Basic protocol to talk with the ESP-Link modul
pub struct Protocol {
buffer: u8,
buffer_size: u16,
data_length: u16,
is_esc: u8, // bool instead?
}
struct Esp<T>
where T: Any + Usart,
{
serial: Serial<'static, T>,
timeout: u32,
}
impl<T> Esp<T>
where
T: Any + Usart,
{
pub fn new(s: Serial<'static, T>, t: u32) -> Esp<T> {
Esp {
serial: s.clone(),
timeout: t,
}
}
pub fn sync(&self) {
let _serial = self.serial;
//serial.write(SlipCodes::SlipEnd); // send a END character to make sure the serial line is clear
}
pub fn process() {}
pub fn request(&self) {}
}
use core;
use smoltcp::{self, phy::{self, DeviceCapabilities}, time::Instant, wire::EthernetAddress};
const ETH_BUF_SIZE: usize = 1536;
const ETH_NUM_TD: usize = 4;
const ETH_NUM_RD: usize = 4;
use ::main::ETH_PHY_ADDR;
/// Transmit Descriptor representation
///
/// * tdes0: ownership bit and transmit settings
/// * tdes1: transmit buffer lengths
/// * tdes2: transmit buffer address
/// * tdes3: not used
///
/// Note that Copy and Clone are derived to support initialising an array of TDes,
/// but you may not move a TDes after its address has been given to the ETH_DMA engine.
#[derive(Copy,Clone)]
#[repr(C,packed)]
struct TDes {
tdes0: u32,
tdes1: u32,
tdes2: u32,
tdes3: u32,
}
impl TDes {
/// Initialises this TDes to point at the given buffer.
pub fn init(&mut self, tdbuf: &[u32]) {
// Set FS and LS on each descriptor: each will hold a single full segment.
self.tdes0 = (1<<29) | (1<<28);
// Store pointer to associated buffer.
self.tdes2 = tdbuf.as_ptr() as u32;
// No second buffer.
self.tdes3 = 0;
}
/// Mark this TDes as end-of-ring.
pub fn set_end_of_ring(&mut self) {
self.tdes0 |= 1<<21;
}
/// Return true if the RDes is not currently owned by the DMA
pub fn available(&self) -> bool {
self.tdes0 & (1<<31) == 0
}
/// Release this RDes back to DMA engine for transmission
pub fn release(&mut self) {
self.tdes0 |= 1<<31;
}
/// Set the length of data in the buffer ponited to by this TDes
pub fn set_length(&mut self, length: usize) {
self.tdes1 = (length as u32) & 0x1FFF;
}
/// Access the buffer pointed to by this descriptor
pub unsafe fn buf_as_slice_mut(&self) -> &mut [u8] {
core::slice::from_raw_parts_mut(self.tdes2 as *mut _, self.tdes1 as usize & 0x1FFF)
}
}
/// Store a ring of TDes and associated buffers
struct TDesRing {
td: [TDes; ETH_NUM_TD],
tbuf: [[u32; ETH_BUF_SIZE/4]; ETH_NUM_TD],
tdidx: usize,
}
static mut TDESRING: TDesRing = TDesRing {
td: [TDes { tdes0: 0, tdes1: 0, tdes2: 0, tdes3: 0 }; ETH_NUM_TD],
tbuf: [[0; ETH_BUF_SIZE/4]; ETH_NUM_TD],
tdidx: 0,
};
impl TDesRing {
/// Initialise this TDesRing
///
/// The current memory address of the buffers inside this TDesRing will be stored in the
/// descriptors, so ensure the TDesRing is not moved after initialisation.
pub fn init(&mut self) {
for (td, tdbuf) in self.td.iter_mut().zip(self.tbuf.iter()) {
td.init(&tdbuf[..]);
}
self.td.last_mut().unwrap().set_end_of_ring();
}
/// Return the address of the start of the TDes ring
pub fn ptr(&self) -> *const TDes {
self.td.as_ptr()
}
/// Return true if a TDes is available for use
pub fn available(&self) -> bool {
self.td[self.tdidx].available()
}
/// Return the next available TDes if any are available, otherwise None
pub fn next(&mut self) -> Option<&mut TDes> {
if self.available() {
let rv = Some(&mut self.td[self.tdidx]);
self.tdidx = (self.tdidx + 1) % ETH_NUM_TD;
rv
} else {
None
}
}
}
/// Receive Descriptor representation
///
/// * rdes0: ownership bit and received packet metadata
/// * rdes1: receive buffer lengths and settings
/// * rdes2: receive buffer address
/// * rdes3: not used
///
/// Note that Copy and Clone are derived to support initialising an array of TDes,
/// but you may not move a TDes after its address has been given to the ETH_DMA engine.
#[derive(Copy,Clone)]
#[repr(C,packed)]
struct RDes {
rdes0: u32,
rdes1: u32,
rdes2: u32,
rdes3: u32,
}
impl RDes {
/// Initialises this RDes to point at the given buffer.
pub fn init(&mut self, rdbuf: &[u32]) {
// Mark each RDes as owned by the DMA engine.
self.rdes0 = 1<<31;
// Store length of and pointer to associated buffer.
self.rdes1 = rdbuf.len() as u32 * 4;
self.rdes2 = rdbuf.as_ptr() as u32;
// No second buffer.
self.rdes3 = 0;
}
/// Mark this RDes as end-of-ring.
pub fn set_end_of_ring(&mut self) {
self.rdes1 |= 1<<15;
}
/// Return true if the RDes is not currently owned by the DMA
pub fn available(&self) -> bool {
self.rdes0 & (1<<31) == 0
}
/// Release this RDes back to the DMA engine
pub fn release(&mut self) {
self.rdes0 |= 1<<31;
}
/// Access the buffer pointed to by this descriptor
pub unsafe fn buf_as_slice(&self) -> &[u8] {
core::slice::from_raw_parts(self.rdes2 as *const _, (self.rdes0 >> 16) as usize & 0x3FFF)
}
}
/// Store a ring of RDes and associated buffers
struct RDesRing {
rd: [RDes; ETH_NUM_RD],
rbuf: [[u32; ETH_BUF_SIZE/4]; ETH_NUM_RD],
rdidx: usize,
}
static mut RDESRING: RDesRing = RDesRing {
rd: [RDes { rdes0: 0, rdes1: 0, rdes2: 0, rdes3: 0 }; ETH_NUM_RD],
rbuf: [[0; ETH_BUF_SIZE/4]; ETH_NUM_RD],
rdidx: 0,
};
impl RDesRing {
/// Initialise this RDesRing
///
/// The current memory address of the buffers inside this TDesRing will be stored in the
/// descriptors, so ensure the TDesRing is not moved after initialisation.
pub fn init(&mut self) {
for (rd, rdbuf) in self.rd.iter_mut().zip(self.rbuf.iter()) {
rd.init(&rdbuf[..]);
}
self.rd.last_mut().unwrap().set_end_of_ring();
}
/// Return the address of the start of the RDes ring
pub fn ptr(&self) -> *const RDes {
self.rd.as_ptr()
}
/// Return true if a RDes is available for use
pub fn available(&self) -> bool {
self.rd[self.rdidx].available()
}
/// Return the next available RDes if any are available, otherwise None
pub fn next(&mut self) -> Option<&mut RDes> {
if self.available() {
let rv = Some(&mut self.rd[self.rdidx]);
self.rdidx = (self.rdidx + 1) % ETH_NUM_RD;
rv
} else {
None
}
}
}
/// Ethernet device driver
pub struct EthernetDevice {
rdring: &'static mut RDesRing,
tdring: &'static mut TDesRing,
eth_mac: stm32f407::ETHERNET_MAC,
eth_dma: stm32f407::ETHERNET_DMA,
}
impl EthernetDevice {
/// Create a new uninitialised EthernetDevice.
///
/// You must move in ETH_MAC, ETH_DMA, and they are then kept by the device.
pub fn new(eth_mac: stm32f407::ETHERNET_MAC, eth_dma: stm32f407::ETHERNET_DMA)
-> EthernetDevice {
unsafe { EthernetDevice { rdring: &mut RDESRING, tdring: &mut TDESRING, eth_mac, eth_dma }}
}
/// Initialise the ethernet driver.
///
/// Sets up the descriptor structures, sets up the peripheral clocks and GPIO configuration,
/// and configures the ETH MAC and DMA peripherals.
///
/// Brings up the PHY and then blocks waiting for a network link.
pub fn init(&mut self, rcc: &mut stm32f407::RCC, addr: EthernetAddress) {
self.tdring.init();
self.rdring.init();
self.init_peripherals(rcc, addr);
self.phy_reset();
self.phy_init();
}
pub fn link_established(&mut self) -> bool {
return self.phy_poll_link()
}
pub fn block_until_link(&mut self) {
while !self.link_established() {}
}
/// Resume suspended TX DMA operation
pub fn resume_tx_dma(&mut self) {
if self.eth_dma.dmasr.read().tps().is_suspended() {
self.eth_dma.dmatpdr.write(|w| w.tpd().poll());
}
}
/// Resume suspended RX DMA operation
pub fn resume_rx_dma(&mut self) {
if self.eth_dma.dmasr.read().rps().is_suspended() {
self.eth_dma.dmarpdr.write(|w| w.rpd().poll());
}
}
/// Sets up the device peripherals.
fn init_peripherals(&mut self, rcc: &mut stm32f407::RCC, mac: EthernetAddress) {
// Reset ETH_MAC and ETH_DMA
rcc.ahb1rstr.modify(|_, w| w.ethmacrst().reset());
rcc.ahb1rstr.modify(|_, w| w.ethmacrst().clear_bit());
self.eth_dma.dmabmr.modify(|_, w| w.sr().reset());
while self.eth_dma.dmabmr.read().sr().is_reset() {}
// Set MAC address
let mac = mac.as_bytes();
self.eth_mac.maca0lr.write(|w| w.maca0l().bits(
(mac[0] as u32) << 0 | (mac[1] as u32) << 8 |
(mac[2] as u32) <<16 | (mac[3] as u32) <<24));
self.eth_mac.maca0hr.write(|w| w.maca0h().bits(
(mac[4] as u16) << 0 | (mac[5] as u16) << 8));
// Enable RX and TX. We'll set link speed and duplex at link-up.
self.eth_mac.maccr.write(|w|
w.re().enabled()
.te().enabled()
.cstf().enabled()
);
// Tell the ETH DMA the start of each ring
self.eth_dma.dmatdlar.write(|w| w.stl().bits(self.tdring.ptr() as u32));
self.eth_dma.dmardlar.write(|w| w.srl().bits(self.rdring.ptr() as u32));
// Set DMA bus mode
self.eth_dma.dmabmr.modify(|_, w|
w.aab().aligned()
.pbl().pbl1()
);
// Flush TX FIFO
self.eth_dma.dmaomr.write(|w| w.ftf().flush());
while self.eth_dma.dmaomr.read().ftf().is_flush() {}
// Set DMA operation mode to store-and-forward and start DMA
self.eth_dma.dmaomr.write(|w|
w.rsf().store_forward()
.tsf().store_forward()
.st().started()
.sr().started()
);
}
/// Read a register over SMI.
fn smi_read(&mut self, reg: u8) -> u16 {
// Use PHY address 00000, set register address, set clock to HCLK/102, start read.
self.eth_mac.macmiiar.write(|w|
w.mb().busy()
.pa().bits(ETH_PHY_ADDR)
.cr().cr_150_168()
.mr().bits(reg)
);
// Wait for read
while self.eth_mac.macmiiar.read().mb().is_busy() {}
// Return result
self.eth_mac.macmiidr.read().td().bits()
}
/// Write a register over SMI.
fn smi_write(&mut self, reg: u8, val: u16) {
// Use PHY address 00000, set write data, set register address, set clock to HCLK/102,
// start write operation.
self.eth_mac.macmiidr.write(|w| w.td().bits(val));
self.eth_mac.macmiiar.write(|w|
w.mb().busy()
.pa().bits(ETH_PHY_ADDR)
.mw().write()
.cr().cr_150_168()
.mr().bits(reg)
);
while self.eth_mac.macmiiar.read().mb().is_busy() {}
}
/// Reset the connected PHY and wait for it to come out of reset.
fn phy_reset(&mut self) {
self.smi_write(0x00, 1<<15);
while self.smi_read(0x00) & (1<<15) == (1<<15) {}
}
/// Command connected PHY to initialise.
fn phy_init(&mut self) {
self.smi_write(0x00, 1<<12);
}
/// Poll PHY to determine link status.
fn phy_poll_link(&mut self) -> bool {
let bsr = self.smi_read(0x01);
let bcr = self.smi_read(0x00);
let lpa = self.smi_read(0x05);
// No link without autonegotiate
if bcr & (1<<12) == 0 { return false; }
// No link if link is down
if bsr & (1<< 2) == 0 { return false; }
// No link if remote fault
if bsr & (1<< 4) != 0 { return false; }
// No link if autonegotiate incomplete
if bsr & (1<< 5) == 0 { return false; }
// No link if other side can't do 100Mbps full duplex
if lpa & (1<< 8) == 0 { return false; }
// Got link. Configure MAC to 100Mbit/s and full duplex.
self.eth_mac.maccr.modify(|_, w|
w.fes().fes100()
.dm().full_duplex()
);
true
}
}
pub struct TxToken(*mut EthernetDevice);
pub struct RxToken(*mut EthernetDevice);
impl phy::TxToken for TxToken {
fn consume<R, F>(self, _timestamp: Instant, len: usize, f: F) -> smoltcp::Result<R>
where F: FnOnce(&mut [u8]) -> smoltcp::Result<R>
{
let tdes = unsafe { (*self.0).tdring.next().unwrap() };
tdes.set_length(len);
let result = f(unsafe { tdes.buf_as_slice_mut() });
tdes.release();
unsafe { (*self.0).resume_tx_dma() };
result
}
}
impl phy::RxToken for RxToken {
fn consume<R, F>(self, _timestamp: Instant, f: F) -> smoltcp::Result<R>
where F: FnOnce(&[u8]) -> smoltcp::Result<R>
{
let rdes = unsafe { (*self.0).rdring.next().unwrap() };
let result = f(unsafe { rdes.buf_as_slice() });
rdes.release();
unsafe { (*self.0).resume_rx_dma() };
result
}
}
// Implement the smoltcp Device interface
impl<'a> phy::Device<'a> for EthernetDevice {
type RxToken = RxToken;
type TxToken = TxToken;
fn capabilities(&self) -> DeviceCapabilities {
let mut caps = DeviceCapabilities::default();
caps.max_transmission_unit = 1500;
caps.max_burst_size = Some(core::cmp::min(ETH_NUM_TD, ETH_NUM_RD));
caps
}
fn receive(&mut self) -> Option<(RxToken, TxToken)> {
if self.rdring.available() && self.tdring.available() {
Some((RxToken(self), TxToken(self)))
} else {
None
}
}
fn transmit(&mut self) -> Option<TxToken> {
if self.tdring.available() {
Some(TxToken(self))
} else {
None
}
}
}
\ No newline at end of file
#![deny(unsafe_code)]
#![deny(warnings)]
#![feature(proc_macro)]
#![no_std]
extern crate cortex_m;
#[macro_use]
extern crate cortex_m_debug;
extern crate cortex_m_rtfm as rtfm;
extern crate f4;
extern crate heapless;
//extern crate smoltcp;
extern crate stm32f40x;
// CORE
use core::result::Result;
//use core::str;
// RTFM
use rtfm::{app, Resource, Threshold};
// F4
use f4::prelude::*;
use f4::{clock, I2c, Serial, Timer};
use f4::serial::Event;
use f4::time::{Hertz, Seconds};
use stm32f40x::I2C1;
// SMOLTCP
/*
use smoltcp::phy::Loopback;
use smoltcp::wire::{EthernetAddress, IpAddress, IpCidr};
use smoltcp::iface::{EthernetInterfaceBuilder, NeighborCache};
use smoltcp::socket::{SocketSet, TcpSocket, TcpSocketBuffer};
use smoltcp::time::{Duration, Instant};
*/
// SLIP
// mod slip;
// ESP-LINK
mod esp;
// CONFIGURATION
pub const TCP_PORT: u16 = 7777;
pub const ETH_PHY_ADDR: u8 = 1;
//const MAX_UDP_PACKET_SIZE: usize = 2048;
const BAUD_RATE: Hertz = Hertz(115_200);
const I2C_BUFFER_SIZE: usize = core::mem::size_of::<u32>();
const SENSOR_READ_TIME: Seconds = Seconds(60); // corresponds to ~20 sec for some reson. Maybe something with the increased clockspeed.
#[derive(Debug)]
pub enum Error {
StaleData,
CommandMode,
Unknown,
}
app! {
device: f4::stm32f40x,
resources: {
static TEMPERATURE: f32 = 0.0;
static HUMIDITY: f32 = 0.0;
//static PACKET: Vec<u8, [u8; MAX_UDP_PACKET_SIZE]> = Vec::new();
},
tasks: {
USART2: {
path: rx,
priority: 2,
resources: [USART2, TEMPERATURE, HUMIDITY],
},
EXTI1: {
path: read_sensor,
priority: 4,
resources: [I2C1, TEMPERATURE, HUMIDITY],
},
/*
EXTI2: {
path: udp_server,
priority: 1,
resources: [PACKET],
},
*/
TIM2: {
path: sensor_update,
priority: 3,
resources: [TIM2],
},
},
}
fn init(p: init::Peripherals, _r: init::Resources) {
// Set clock to higher than default in order to test that it works
clock::set_84_mhz(&p.RCC, &p.FLASH);
// Start the serial port
let serial = Serial(p.USART2);
serial.init(BAUD_RATE.invert(), None, p.GPIOA, p.RCC);
serial.listen(Event::Rxne);
// Listen to serial input on the receive DMA
//serial.read_exact(p.DMA1, r.RX_BUFFER).unwrap();
// Start the I2C peripheral
let i2c = I2c(p.I2C1);
i2c.init(p.GPIOA, p.GPIOB, p.RCC);
i2c.enable();
// Start the timer for the update of the Temp/RH sensor.
let timer = Timer(&*p.TIM2);
timer.init(SENSOR_READ_TIME, p.RCC);
timer.resume();
}
/// Recives the data on the serial interface
fn rx(_t: &mut Threshold, r: USART2::Resources) {
// Serial interface
let serial = Serial(&**r.USART2);
// Match to the byte read
let msg = serial.read();
match msg {
Ok(byte) => {
match byte {
b'd' => {
// DEBUG
let mut _temp: f32 = 0.0;
let mut _rh: f32 = 0.0;
r.TEMPERATURE.claim(_t, |temp, _| {
_temp = **temp;
});
r.HUMIDITY.claim(_t, |rh, _| {
_rh = **rh;
});
sprintln!("Temp: {}", _temp);
sprintln!("RH: {}", _rh);
//let test: u8 = _temp as u8;
//serial.write(test).unwrap();
}
_ => serial.write(byte).unwrap(),
}
}
Err(_) => {
r.USART2.dr.read(); // clear the error by reading the data register
}
}
rtfm::set_pending(f4::stm32f40x::Interrupt::EXTI2);
}
/*
fn udp_server(_t: &mut Threshold _r: EXTI2::Resources) {
}
*/
/// Interrupt for the timer for the update of the Temp/RH sensor.
fn sensor_update(_t: &mut Threshold, r: TIM2::Resources) {
r.TIM2.sr.modify(|_, w| w.uif().clear_bit());
// Sets a new sensor read as a pending task
rtfm::set_pending(f4::stm32f40x::Interrupt::EXTI1);
}
/// Reads and interpretes the sensor data.
fn read_sensor(_t: &mut Threshold, r: EXTI1::Resources) {
// I2C interface.
let i2c = I2c(&**r.I2C1);
// 4 Byte buffer to store the sensor data in.
let mut rx: [u8; I2C_BUFFER_SIZE] = [0; I2C_BUFFER_SIZE];
match get_data(&i2c, &mut rx) {
Err(err) => match err {
Error::StaleData => {
sprintln!("SENSOR ERROR: Sensor has Stale data");
}
Error::CommandMode => {
sprintln!("SENSOR ERROR: Sensor in command mode");
}
Error::Unknown => {
sprintln!("SENSOR ERROR: Sensor displayed unknown error");
}
},
Ok(_) => {
// Overly explicit but the calculation gets mad otherwise.
let mut lt: u16 = rx[3] as u16;
let mut mt: u16 = rx[2] as u16;
let mut lh: u16 = rx[1] as u16;
let mut mh: u16 = rx[0] as u16;
// Calculate temperature and store the value in the resources
let mut temp_count: u16 = mt << 6 | lt >> 2;
let mut _temp: f32 = temp_count as f32 * 165.0 / 16382.0 - 40.0;
// Calculate humidity and store the value in the resources
let mut rh_count: u16 = (mh & 0x3F) << 8 | lh;
let mut _rh: f32 = rh_count as f32 * 100.0 / 16382.0;
// Debugging
//sprintln!("TEMP: {}", _temp);
//sprintln!("RH: {}", _rh);
// Store the values for use in other tasks
r.TEMPERATURE.claim_mut(_t, |temp, _| {
**temp = _temp;
});
r.HUMIDITY.claim_mut(_t, |rh, _| {
**rh = _rh;
});
}
}
}
/// Gets the data from the Temp/RH sensor over the I2C bus
fn get_data(i2c: &I2c<I2C1>, rx_buffer: &mut [u8; I2C_BUFFER_SIZE]) -> Result<(), Error> {
// Send a Measurment Request (MR) to the sensor
while i2c.start(0x4E).is_err() {}
while i2c.stop().is_err() {}
sprintln!("SENSOR READ"); // TODO: NEEDS TO BE SLOWED DOWN, HERE WITH THE USE OF SEMIHOSTING
// Read incoming bytes and ACK them or nack if it is the last byte.
while i2c.start(0x4F).is_err() {}
for i in 0..I2C_BUFFER_SIZE {
rx_buffer[i] = loop {
if i == I2C_BUFFER_SIZE - 1 {
// Do not ACK the last byte received and send STOP
if let Ok(byte) = i2c.read_nack() {
break byte;
}
} else {
// ACK the byte after receiving
if let Ok(byte) = i2c.read_ack() {
break byte;
}
}
}
}
//while i2c.stop().is_err() {}
// Checks the status of the sensor and passes the information on.
let status: u8 = (rx_buffer[0] & 0xC0) >> 6;
match status {
0 => Ok(()),
1 => Err(Error::StaleData),
2 => Err(Error::CommandMode),
3 => Err(Error::Unknown),
_ => Err(Error::Unknown),
}
}
fn idle() -> ! {
loop {
rtfm::wfi();
}
}
use core::fmt::Write;
use smoltcp;
use smoltcp::time::Instant;
use smoltcp::wire::{EthernetAddress, IpAddress, IpCidr};
use smoltcp::iface::{Neighbor, NeighborCache, EthernetInterface, EthernetInterfaceBuilder};
use smoltcp::socket::{SocketSet, SocketSetItem, SocketHandle, TcpSocket, TcpSocketBuffer};
use byteorder::{ByteOrder, LittleEndian};
use ::flash;
use ::build_info;
use ::Error;
use ethernet::EthernetDevice;
const CMD_INFO: u32 = 0;
const CMD_READ: u32 = 1;
const CMD_ERASE: u32 = 2;
const CMD_WRITE: u32 = 3;
const CMD_BOOT: u32 = 4;
use ::config::TCP_PORT;
/// Read an address and length from the socket
fn read_adr_len(socket: &mut TcpSocket) -> (u32, usize) {
let mut adr = [0u8; 4];
let mut len = [0u8; 4];
socket.recv_slice(&mut adr[..]).ok();
socket.recv_slice(&mut len[..]).ok();
let adr = LittleEndian::read_u32(&adr);
let len = LittleEndian::read_u32(&len);
(adr, len as usize)
}
/// Send a status word back at the start of a response
fn send_status(socket: &mut TcpSocket, status: ::Error) {
let mut resp = [0u8; 4];
LittleEndian::write_u32(&mut resp, status as u32);
socket.send_slice(&resp).unwrap();
}
/// Respond to the information request command with our build information.
fn cmd_info(socket: &mut TcpSocket) {
// Read the device unique ID
let id1: u32 = unsafe { *(0x1FFF_7A10 as *const u32) };
let id2: u32 = unsafe { *(0x1FFF_7A14 as *const u32) };
let id3: u32 = unsafe { *(0x1FFF_7A18 as *const u32) };
send_status(socket, Error::Success);
write!(socket, "blethrs {} {}\r\nBuilt: {}\r\nCompiler: {}\r\nMCU ID: {:08X}{:08X}{:08X}\r\n",
build_info::PKG_VERSION, build_info::GIT_VERSION.unwrap(), build_info::BUILT_TIME_UTC,
build_info::RUSTC_VERSION, id1, id2, id3).ok();
}
fn cmd_read(socket: &mut TcpSocket) {
let (adr, len) = read_adr_len(socket);
match flash::read(adr, len) {
Ok(data) => {
send_status(socket, Error::Success);
socket.send_slice(data).unwrap();
},
Err(err) => send_status(socket, err),
};
}
fn cmd_erase(socket: &mut TcpSocket) {
let (adr, len) = read_adr_len(socket);
match flash::erase(adr, len) {
Ok(()) => send_status(socket, Error::Success),
Err(err) => send_status(socket, err),
}
}
fn cmd_write(socket: &mut TcpSocket) {
let (adr, len) = read_adr_len(socket);
match socket.recv(|buf| (buf.len(), flash::write(adr, len, buf))) {
Ok(Ok(())) => send_status(socket, Error::Success),
Ok(Err(err)) => send_status(socket, err),
Err(_) => send_status(socket, Error::NetworkError),
}
}
fn cmd_boot(socket: &mut TcpSocket) {
send_status(socket, Error::Success);
::schedule_reset(50);
}
// Stores the underlying data buffers. If these were included in Network,
// they couldn't live in BSS and therefore take up a load of flash space.
struct NetworkBuffers {
tcp_tx_buf: [u8; 1536],
tcp_rx_buf: [u8; 1536],
}
static mut NETWORK_BUFFERS: NetworkBuffers = NetworkBuffers {
tcp_tx_buf: [0u8; 1536],
tcp_rx_buf: [0u8; 1536],
};
// Stores all the smoltcp required structs.
pub struct Network<'a> {
neighbor_cache_storage: [Option<(IpAddress, Neighbor)>; 16],
ip_addr: Option<[IpCidr; 1]>,
eth_iface: Option<EthernetInterface<'a, 'a, EthernetDevice>>,
sockets_storage: [Option<SocketSetItem<'a, 'a>>; 1],
sockets: Option<SocketSet<'a, 'a, 'a>>,
tcp_handle: Option<SocketHandle>,
initialised: bool,
}
pub static mut NETWORK: Network = Network {
neighbor_cache_storage: [None; 16],
ip_addr: None,
eth_iface: None,
sockets_storage: [None],
sockets: None,
tcp_handle: None,
initialised: false,
};
/// Initialise the static NETWORK.
///
/// Sets up the required EthernetInterface and sockets.
pub unsafe fn init<'a>(eth_dev: EthernetDevice, mac_addr: EthernetAddress, ip_addr: IpCidr) {
let neighbor_cache = NeighborCache::new(&mut NETWORK.neighbor_cache_storage.as_mut()[..]);
NETWORK.ip_addr = Some([ip_addr]);
NETWORK.eth_iface = Some(EthernetInterfaceBuilder::new(eth_dev)
.ethernet_addr(mac_addr)
.neighbor_cache(neighbor_cache)
.ip_addrs(&mut NETWORK.ip_addr.as_mut().unwrap()[..])
.finalize());
NETWORK.sockets = Some(SocketSet::new(&mut NETWORK.sockets_storage.as_mut()[..]));
let tcp_rx_buf = TcpSocketBuffer::new(&mut NETWORK_BUFFERS.tcp_rx_buf.as_mut()[..]);
let tcp_tx_buf = TcpSocketBuffer::new(&mut NETWORK_BUFFERS.tcp_tx_buf.as_mut()[..]);
let tcp_socket = TcpSocket::new(tcp_rx_buf, tcp_tx_buf);
NETWORK.tcp_handle = Some(NETWORK.sockets.as_mut().unwrap().add(tcp_socket));
NETWORK.initialised = true;
}
/// Poll network stack.
///
/// Arrange for this function to be called frequently.
pub fn poll(time_ms: i64) {
unsafe {
// Bail out early if NETWORK is not initialised.
if !NETWORK.initialised {
return;
}
let sockets = NETWORK.sockets.as_mut().unwrap();
// Handle TCP
{
let mut socket = sockets.get::<TcpSocket>(NETWORK.tcp_handle.unwrap());
if !socket.is_open() {
socket.listen(TCP_PORT).unwrap();
}
if !socket.may_recv() && socket.may_send() {
socket.close();
}
if socket.can_recv() {
let mut cmd = [0u8; 4];
socket.recv_slice(&mut cmd[..]).ok();
let cmd = LittleEndian::read_u32(&cmd[..]);
match cmd {
CMD_INFO => cmd_info(&mut socket),
CMD_READ => cmd_read(&mut socket),
CMD_ERASE => cmd_erase(&mut socket),
CMD_WRITE => cmd_write(&mut socket),
CMD_BOOT => cmd_boot(&mut socket),
_ => (),
};
socket.close();
}
}
// Poll smoltcp
let timestamp = Instant::from_millis(time_ms);
match NETWORK.eth_iface.as_mut().unwrap().poll(sockets, timestamp) {
Ok(_) | Err(smoltcp::Error::Exhausted) => (),
Err(_) => (),
}
}
}
\ No newline at end of file
#![allow(dead_code)]
use heapless::RingBuffer;
use f4::Serial;
/// Codes used by slip
#[derive(PartialEq)] // Fler
pub enum SlipCodes {
SlipEnd = 0xC0, // OCT: 0300
SlipEsc = 0xDB, // OCT: 0333
SlipEscEnd = 0xDC, // OCT: 0334
SlipEscEsc = 0xDE, // OCT: 0335
}
pub struct SlipBuffer {
buffer: RingBuffer<u8, [u8; 4]>,
last: SlipCodes,
packet_count: u8,
}
pub impl SlipBuffer {
pub fn new() -> Self {
SlipBuffer {
buffer: RingBuffer::new(),
last: SlipCodes::SlipEnd,
packet_count: 0,
}
}
}
pub struct SlipPacket {
buffer: SlipBuffer,
}
pub struct Slip {
todo: u8,
}
pub impl Slip {
pub fn send_packet() {}
pub fn read_packet(&mut packet: SlipPacket) -> SlipPacket {
}
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment