Compare commits

..

No commits in common. "dev" and "main" have entirely different histories.
dev ... main

22 changed files with 1155 additions and 1657 deletions

View File

@ -1,9 +1,8 @@
[target.'cfg(all(target_arch = "arm", target_os = "none"))'] [target.'cfg(all(target_arch = "arm", target_os = "none"))']
# runner = "sudo /home/arkitu/.cargo/bin/elf2uf2-rs -d -s" runner = "sudo /home/arkitu/.cargo/bin/elf2uf2-rs -d -s"
runner = "probe-rs run --chip RP2040"
[build] [build]
target = "thumbv6m-none-eabi" # Cortex-M0 and Cortex-M0+ target = "thumbv6m-none-eabi" # Cortex-M0 and Cortex-M0+
[env] [env]
DEFMT_LOG = "info" DEFMT_LOG = "debug"

702
Cargo.lock generated

File diff suppressed because it is too large Load Diff

View File

@ -4,51 +4,48 @@ version = "0.1.0"
edition = "2024" edition = "2024"
[features] [features]
json = ["dep:serde-json-core", "dep:serde"]
wifi-connect = [ wifi-connect = [
"dep:serde-json-core", "dep:serde-json-core",
"dep:serde", "dep:serde",
] # you need to add a wifi.json file for this to work ] # you need to add a wifi.json file for this to work
dhcp = ["dep:dhcparse"] dhcp = ["dep:dhcparse"]
dns = ["dep:dnsparse"] dns = ["dep:dnsparse"]
chat = ["dep:ringbuf", "json"] chat = ["dep:ringbuffer"]
ttt = ["json"] ttt = []
default = ["dhcp", "dns", "chat", "ttt"] default = ["dhcp", "dns"]
[dependencies] [dependencies]
# git = "https://github.com/embassy-rs/embassy", embassy-executor = { git = "https://github.com/embassy-rs/embassy", features = [
embassy-executor = { version = "*", features = [ "defmt",
"nightly", "nightly",
"arch-cortex-m", "arch-cortex-m",
"executor-thread", "executor-thread",
"executor-interrupt", "executor-interrupt",
"defmt"
] } ] }
embassy-rp = { version = "*", features = [ embassy-rp = { git = "https://github.com/embassy-rs/embassy", features = [
"defmt",
"unstable-pac", "unstable-pac",
"rp2040", "rp2040",
"time-driver", "time-driver",
"critical-section-impl", "critical-section-impl",
"defmt"
] } ] }
embassy-time = { version = "*", features = ["defmt"] } embassy-time = { git = "https://github.com/embassy-rs/embassy" }
# embassy-usb-logger = { version = "*" } embassy-usb-logger = { git = "https://github.com/embassy-rs/embassy" }
embassy-net = { version = "*", features = [ embassy-net = { git = "https://github.com/embassy-rs/embassy", features = [
"defmt",
"proto-ipv4", "proto-ipv4",
"tcp", "tcp",
"udp", "udp",
"dhcpv4", "dhcpv4",
"defmt"
] } ] }
embassy-sync = { version = "*", features = ["defmt"] } embassy-sync = { git = "https://github.com/embassy-rs/embassy" }
cyw43-pio = { version = "*", features = ["defmt"] } cyw43-pio = { git = "https://github.com/embassy-rs/embassy" }
cyw43 = { version = "*", features = ["defmt"] } cyw43 = { git = "https://github.com/embassy-rs/embassy" }
defmt = "1.0.1"
defmt-rtt = "1.0.0"
panic-probe = { version = "1.0.0", features = ["print-defmt"] }
embedded-io-async = "*" embedded-io-async = "*"
defmt = "*"
defmt-rtt = "*"
panic-probe = "*"
cortex-m = { version = "*", features = ["inline-asm"] } cortex-m = { version = "*", features = ["inline-asm"] }
cortex-m-rt = "*" cortex-m-rt = "*"
static_cell = "*" static_cell = "*"
@ -63,12 +60,7 @@ serde = { version = "*", optional = true, default-features = false, features = [
] } ] }
dhcparse = { version = "*", default-features = false, optional = true } dhcparse = { version = "*", default-features = false, optional = true }
dnsparse = { version = "*", optional = true } dnsparse = { version = "*", optional = true }
ringbuf = { version = "*", default-features = false, features = [ ringbuffer = { version = "*", default-features = false, optional = true }
"portable-atomic",
], optional = true }
percent-encoding = { version = "*", default-features = false } percent-encoding = { version = "*", default-features = false }
sha1 = { version = "*", default-features = false } sha1 = { version = "*", default-features = false }
base64 = { version = "*", default-features = false } base64 = { version = "*", default-features = false }
anyhow = { version = "*", default-features = false }
embedded-alloc = "*"

View File

@ -1,3 +1,2 @@
[toolchain] [toolchain]
# channel = "nightly-2025-03-18"
channel = "nightly" channel = "nightly"

View File

@ -1,30 +1,41 @@
<!doctype html> <!doctype html>
<head>
<script src="./htmx.js"></script>
<style type="text/css">
body {
/* #grid {
.cell {
border: 1px dotted black;
padding: 33%;
}
display: grid;
border: 1px solid black;
grid-template-rows: 1fr 1fr 1fr;
grid-template-columns: 1fr 1fr 1fr;
} */
}
</style>
</head>
<html> <html>
<head>
<script src="/chat.js" defer></script>
<style>
#users_box {
float: right;
}
</style>
</head>
<body> <body>
<h1>Chat</h1> <h1>Chat</h1>
<div id="users_box"> <form id="login-page">
<h3>Online Users :</h3> Enter your name :
<div id="users"></div>
</div>
<div id="msgs"></div>
<form id="send">
<input <input
id="sendcontent" name="username"
name="content" type="text"
autofocus autocomplete="username"
minlength="3"
maxlength="16"
required required
minlength="1"
maxlength="500"
/> />
<input type="submit" value="Send" /> <button
hx-post="/chat/connect"
hx-target="#login-page"
hx-swap="outerHTML"
>
Connect
</button>
</form> </form>
</body> </body>
</html> </html>

View File

@ -1,48 +0,0 @@
// const id = 0;
if (id === undefined) {
throw "id is undefined!";
}
const ws = new WebSocket("ws://192.254.0.2:" + (9000 + id));
ws.onmessage = (event) => {
console.log(event.data);
if (typeof event.data == "string") {
let msg = JSON.parse(event.data);
if (event.data[0] == "[") {
// Handle list of users
users = msg;
let usersElems = [];
for (u of users) {
if (typeof u == "string") {
let un = document.createElement("div");
un.innerText = u;
usersElems.push(un);
}
}
document.getElementById("users").replaceChildren(...usersElems);
} else {
// Handle message
let msgs = document.getElementById("msgs");
let elem = document.createElement("p");
elem["data-id"] = msg.id;
elem.innerHTML =
"<strong>" + users[msg.author] + " :</strong> " + msg.content;
for (c of msgs.children) {
if (c["data-id"] > msg.id) {
msgs.insertBefore(elem, c);
return;
}
}
msgs.appendChild(elem);
}
}
};
document.getElementById("send").onsubmit = (event) => {
event.preventDefault();
// console.log(event, document.getElementById("sendcontent").value);
let timestamp = Date.now();
let content = document.getElementById("sendcontent");
ws.send("send " + timestamp.toString() + " " + content.value);
content.value = "";
};

View File

@ -1,229 +1,30 @@
use core::{str::from_utf8_unchecked, sync::atomic::Ordering}; use core::fmt::Write;
use dhcparse::dhcpv4::MAX_MESSAGE_SIZE;
use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, mutex::Mutex}; use embassy_sync::{blocking_mutex::raw::ThreadModeRawMutex, mutex::Mutex};
use embassy_time::{Duration, Timer}; use heapless::{String, Vec};
use heapless::String; use log::{info, warn};
// use log::{info, warn}; use percent_encoding::percent_decode_str;
// use pico_website::unimplemented; use pico_website::unwrap;
use anyhow::{Result, anyhow}; use ringbuffer::{ConstGenericRingBuffer, RingBuffer};
use defmt::*;
use portable_atomic::AtomicUsize;
use serde::Serialize;
use crate::{apps::App, socket::ws::WsMsg}; use crate::socket::{HttpRequestType, HttpResCode};
// Must be <= u8::MAX-1; use super::App;
pub const USERS_LEN: u8 = 4;
const MSG_MAX_SIZE: usize = 500; const MEMORY_SIZE: usize = 16;
#[derive(Debug, Serialize)] const USERNAME_MIN_SIZE: usize = 3;
struct Msg<'a> { const USERNAME_SIZE: usize = 16;
id: usize, const MSG_SIZE: usize = 128;
author: u8,
timestamp: u64,
content: &'a str,
}
const MSGS_SIZE: usize = 100000; static MESSAGES: Mutex<ThreadModeRawMutex, Messages> = Mutex::new(Messages::new());
const _: () = core::assert!(MSGS_SIZE > MSG_MAX_SIZE);
#[derive(Debug)]
struct Msgs {
/// * Memory layout with sizes in bytes : ...|content: len|len: 2|delimiter(255)| other_msg/pad(0)...
/// * content = author: 1 | timestamp: 8 | content: len-5
/// * No message is splitted
inner: [u8; MSGS_SIZE],
/// next byte index
head: usize,
next_msg: usize,
}
impl Msgs {
const fn default() -> Self {
Self {
inner: [0; _],
head: 0,
next_msg: 0,
}
}
fn push(&mut self, author: u8, timestamp: u64, content: &str) {
let len = 1 + 8 + content.len();
if self.head + len + 3 >= MSGS_SIZE {
self.inner[self.head..].fill(0);
self.head = 0
}
self.inner[self.head] = author;
self.inner[self.head + 1..self.head + 9].copy_from_slice(&timestamp.to_le_bytes());
self.inner[self.head + 9..self.head + 9 + content.len()]
.copy_from_slice(content.as_bytes());
self.inner[self.head + len..self.head + len + 2]
.copy_from_slice(&(len as u16).to_le_bytes());
self.inner[self.head + len + 2] = u8::MAX;
self.head += len + 3;
self.next_msg += 1;
}
/// Iter messages from present to past
fn iter<'a>(&'a self) -> MsgsIter<'a> {
if self.head == 0 {
MsgsIter {
msgs: self,
head: 0,
current_id: 0,
finished: true,
}
} else {
MsgsIter {
msgs: self,
head: self.head,
current_id: self.next_msg - 1,
finished: false,
}
}
}
}
#[derive(Debug)]
struct MsgsIter<'a> {
msgs: &'a Msgs,
/// next byte index
head: usize,
finished: bool,
current_id: usize,
}
impl<'a> Iterator for MsgsIter<'a> {
type Item = Msg<'a>;
/// We trust msgs.inner validity in this function, it might panic or do UB if msgs.inner is not valid
fn next(&mut self) -> Option<Self::Item> {
if self.finished {
return None;
}
if self.head == 0 {
self.head = MSGS_SIZE;
}
let above = self.head > self.msgs.head;
if above && self.head <= self.msgs.head + 12 {
self.finished = true;
return None;
}
match self.msgs.inner[self.head - 1] {
// Skip padding
0 => {
self.head -= 1;
self.next()
}
u8::MAX => {
let len = u16::from_le_bytes([
self.msgs.inner[self.head - 3],
self.msgs.inner[self.head - 2],
]) as usize;
self.head -= 3 + len;
let author = self.msgs.inner[self.head];
let timestamp = u64::from_le_bytes([
self.msgs.inner[self.head + 1],
self.msgs.inner[self.head + 2],
self.msgs.inner[self.head + 3],
self.msgs.inner[self.head + 4],
self.msgs.inner[self.head + 5],
self.msgs.inner[self.head + 6],
self.msgs.inner[self.head + 7],
self.msgs.inner[self.head + 8],
]);
let content = unsafe {
from_utf8_unchecked(&self.msgs.inner[self.head + 9..self.head + len])
};
let id = self.current_id;
if self.current_id == 0 {
self.finished = true;
} else {
self.current_id -= 1;
}
Some(Msg {
id,
author,
timestamp,
content,
})
}
_ => core::unreachable!(),
}
// if self.msgs.inner[self.head - 1] == 0 {
// return self.next();
// }
// let author = self.msgs.inner[self.head - 1];
// self.head -= 1;
// if author == 0 {
// return self.next();
// }
// let author = author - 1;
// let len = u16::from_le_bytes([
// self.msgs.inner[self.head - 2],
// self.msgs.inner[self.head - 1],
// ]) as usize;
// self.head -= 2;
// let content =
// unsafe { str::from_utf8_unchecked(&self.msgs.inner[self.head - len..self.head]) };
// self.head -= len;
// if above && self.head < self.msgs.head {
// self.finished = true;
// return None;
// }
// let id = self.current_id;
// if self.current_id == 0 {
// self.finished = true;
// } else {
// self.current_id -= 1;
// }
// Some(Msg {
// id,
// author,
// content,
// })
}
}
static MSGS: Mutex<ThreadModeRawMutex, Msgs> = Mutex::new(Msgs::default());
const USERNAME_MAX_LEN: usize = 16;
#[derive(Serialize)]
pub struct Usernames([Option<String<USERNAME_MAX_LEN>>; USERS_LEN as usize]);
impl Usernames {
const fn default() -> Self {
Self([None, None, None, None])
}
pub fn get_id(&mut self, name: &str) -> Option<u8> {
for (i, un) in self.0.iter().enumerate() {
if let Some(n) = un {
if n.as_str() == name {
return Some(i as u8);
}
}
}
for (i, un) in self.0.iter_mut().enumerate() {
if *un == None {
*un = Some(String::new());
un.as_mut().unwrap().push_str(name).unwrap();
USERNAMES_VERSION.add(1, Ordering::Relaxed);
return Some(i as u8);
}
}
None
}
}
pub static USERNAMES: Mutex<ThreadModeRawMutex, Usernames> = Mutex::new(Usernames::default());
pub static USERNAMES_VERSION: AtomicUsize = AtomicUsize::new(0);
pub struct ChatApp { pub struct ChatApp {
id: u8, res_buf: String<1100>,
/// Id of the next message to send to client (so that 0 means no message has been sent)
next_msg: usize,
usernames_version: usize,
} }
impl ChatApp { impl ChatApp {
pub fn new(id: u8) -> Self { pub fn new() -> Self {
Self { Self {
id, res_buf: String::new(),
next_msg: 0,
usernames_version: 0,
} }
} }
} }
@ -231,102 +32,245 @@ impl App for ChatApp {
fn socket_name(&self) -> &'static str { fn socket_name(&self) -> &'static str {
"chat" "chat"
} }
fn accept_ws(&self, path: &str) -> bool { async fn handle_request<'a>(
path == "/" &'a mut self,
} path: &str,
async fn handle_ws<const BUF_SIZE: usize>( req_type: HttpRequestType,
&mut self, content: &str,
_path: &str, ) -> (HttpResCode, &'static str, &'a str) {
mut ws: crate::socket::ws::Ws<'_, BUF_SIZE>, match (req_type, path) {
) { (HttpRequestType::Get, "/" | "/index" | "/index.html" | "/chat" | "/chat.html") => {
self.usernames_version = 0; (HttpResCode::Ok, "html", include_str!("./chat.html"))
self.next_msg = 0; }
Timer::after_millis(500).await; (_, path) => {
let r: Result<()> = try { let (path, args) = path.split_once('?').unwrap_or((path, ""));
'ws: { let mut load = None;
loop { let mut username = None;
Timer::after_millis(1).await; let mut msg_content = None;
{ let mut poll = false;
let uv = USERNAMES_VERSION.load(Ordering::Relaxed); for arg in args.split('&').chain(content.split('&')) {
if self.usernames_version < uv { match arg.split_once('=') {
ws.send_json(&(*USERNAMES.lock().await)).await?; Some(("load", n)) => {
} let n: u16 = match n.parse() {
self.usernames_version = uv; Ok(v) => v,
} Err(_) => return (HttpResCode::BadRequest, "", ""),
{ };
let msgs = MSGS.lock().await; if n > 0 {
for m in msgs.iter() { load = Some(n);
if m.id >= self.next_msg {
ws.send_json(&m).await?;
} }
} }
self.next_msg = msgs.next_msg; Some(("username", u)) => {
} let mut name = String::<USERNAME_SIZE>::new();
if ws.last_msg.elapsed() >= Duration::from_secs(5) { for c in percent_decode_str(u) {
ws.send(WsMsg::Ping(&[])).await?; if let Err(_) = name.push(c as char) {
} return (HttpResCode::BadRequest, "", "");
while let Some(r) = ws.rcv().await? {
info!("{:?}", r);
if let WsMsg::Text(r) = r {
match r.split_once(' ') {
Some(("send", m)) => {
let (t, msg) = m
.split_once(' ')
.ok_or(anyhow!("message cannot be splitted with ' '"))?;
info!("{}", t);
let timestamp = t.parse::<u64>()?;
if msg.len() > MSG_MAX_SIZE {
warn!("Message too long! (len={})", r.len() - 5);
break 'ws;
}
MSGS.lock().await.push(self.id, timestamp, msg);
} }
_ => {}
} }
// if r.starts_with("send ") { if u.len() < USERNAME_MIN_SIZE {
// if r.len() > 5 + MSG_MAX_SIZE { return (HttpResCode::BadRequest, "", "");
// warn!("Message too long! (len={})", r.len() - 5); }
// break 'ws; username = Some(name);
// }
// {
// MSGS.lock()
// .await
// .push(self.id, r.get(5..).unwrap_or_default());
// }
// }
} }
Some(("msg", m)) => {
let mut msg = Vec::<u8, MSG_SIZE>::new();
let mut i = 0;
while i < m.len() {
let c = if m.as_bytes()[i] == b'%' {
let c = match m
.get(i + 1..=i + 2)
.map(|s| u8::from_str_radix(s, 16))
{
Some(Ok(c)) => c,
_ => {
warn!("Invalid percent encoding of msg argument");
return (HttpResCode::BadRequest, "", "");
}
};
i += 2;
c
} else {
m.as_bytes()[i]
};
if let Err(_) = msg.push(c) {
return (HttpResCode::BadRequest, "", "");
}
i += 1;
}
msg_content = Some(match String::from_utf8(msg) {
Ok(msg) => msg,
Err(_) => {
warn!("Invalid utf8 msg argument");
return (HttpResCode::BadRequest, "", "");
}
});
}
Some(("poll", "true")) => poll = true,
_ => {}
} }
} }
info!(
"load:{:?} | username:{:?} | msg:{:?}",
load, username, msg_content
);
if path == "/chat/connect" && username.is_some() {
self.res_buf.clear();
unwrap(write!(
&mut self.res_buf,
"<input id=\"username\" style=\"display: none;\" name=\"username\" value=\"{}\">
<div id=\"messages\" >\
<div \
class=\"message\" \
hx-get=\"/chat/message/0?load={}\" \
hx-target=\"this\" \
hx-swap=\"outerHTML\" \
hx-trigger=\"load\" \
></div>\
</div>\
<form id=\"send-message\" \
hx-post=\"/chat/send\" \
hx-include=\"#username\" \
hx-target=\"this\" \
hx-swap=\"innerHTML\"\
>\
<input \
id=\"msg\" \
name=\"msg\" \
maxlength=\"{}\"\
>\
<button>Send</button>
</form>",
username.unwrap(),
MEMORY_SIZE,
MAX_MESSAGE_SIZE
))
.await;
return (HttpResCode::Ok, "html", &self.res_buf);
} else if path == "/chat/send" && username.is_some() && msg_content.is_some() {
let mut msgs = MESSAGES.lock().await;
msgs.push(Message {
author: username.unwrap(),
content: msg_content.unwrap(),
});
self.res_buf.clear();
unwrap(write!(
&mut self.res_buf,
"<input \
id=\"msg\" \
name=\"msg\" \
maxlength=\"{}\"\
>\
<button>Send</button>",
MAX_MESSAGE_SIZE
))
.await;
return (HttpResCode::Ok, "html", &self.res_buf);
} else if path.starts_with("/chat/message/") && path.len() > 14 {
let msg_id: u16 = match path[14..].parse() {
Ok(n) => n,
Err(_) => return (HttpResCode::BadRequest, "", ""),
};
let msgs = MESSAGES.lock().await;
if msg_id > msgs.next {
return (HttpResCode::BadRequest, "", "");
}
self.res_buf.clear();
unwrap(write!(&mut self.res_buf, "<div class=\"message\"")).await;
if msg_id == msgs.next {
if poll {
return (HttpResCode::NoContent, "", "");
}
unwrap(write!(
&mut self.res_buf,
" style=\"display: none;\" \
hx-get=\"/chat/message/{}?load={}&poll=true\" \
hx-target=\"this\" \
hx-swap=\"outerHTML\" \
hx-trigger=\"every 1s\"",
msg_id,
load.unwrap_or(0)
))
.await;
} else {
if let Some(n) = load {
unwrap(write!(
&mut self.res_buf,
" hx-get=\"/chat/message/{}?load={}\" \
hx-target=\"this\" \
hx-swap=\"afterend\" \
hx-trigger=\"load\"",
msg_id + 1,
n - 1,
))
.await;
}
match msgs.get_abs(msg_id) {
Some(msg) => {
unwrap(write!(
&mut self.res_buf,
"><b>{}</b>: {}</div>",
msg.author, msg.content
))
.await
}
None => {
if load.is_some() {
if (msg_id as isize)
== (msgs.next as isize - MEMORY_SIZE as isize - 1)
{
unwrap(write!(
&mut self.res_buf,
"><em>Older messages forgotten</em></div>"
))
.await;
} else {
unwrap(write!(
&mut self.res_buf,
" style=\"display: none;\"></div>"
))
.await;
}
} else {
return (HttpResCode::NoContent, "", "");
}
}
};
};
return (HttpResCode::Ok, "html", &self.res_buf);
} else {
(HttpResCode::NotFound, "", "")
}
} }
};
if let Err(e) = r {
warn!(
"Socket {}: error in ws\n{}",
self.socket_name(),
Display2Format(&e)
);
} }
} }
} }
pub async fn id_to_static_str(id: u8) -> &'static str { struct Message {
match id { author: String<USERNAME_SIZE>,
0 => "0", content: String<MSG_SIZE>,
1 => "1", }
2 => "2",
3 => "3", struct Messages {
4 => "4", inner: ConstGenericRingBuffer<Message, MEMORY_SIZE>,
5 => "5", next: u16,
6 => "6", }
7 => "7", impl Messages {
8 => "8", const fn new() -> Self {
9 => "9", Self {
10 => "10", inner: ConstGenericRingBuffer::new(),
11 => "11", next: 0,
12 => "12", }
13 => "13", }
14 => "14", fn get_abs(&self, id: u16) -> Option<&Message> {
15 => "15", if (id as isize) < (self.next as isize - MEMORY_SIZE as isize) {
_ => defmt::unimplemented!(), return None;
}
self.inner.get_signed((id as isize) - (self.next as isize))
}
fn push(&mut self, msg: Message) {
info!("{}: {}", msg.author, msg.content);
self.inner.push(msg);
self.next += 1;
} }
} }

View File

@ -1,10 +1,15 @@
<!doctype html> <!doctype html>
<head>
<script>
var ws = new WebSocket("/chat");
</script>
</head>
<html> <html>
<body> <body>
<h1>Apps</h1> <h1>Apps</h1>
<ul> <ul>
<li><a href="/ttt?team=0">Tic Tac Toe</a> (team blue)</li> <li><a href="http://pico.wifi:8080">Tic Tac Toe</a> (team blue)</li>
<li><a href="/ttt?team=1">Tic Tac Toe</a> (team red)</li> <li><a href="http://pico.wifi:8081">Tic Tac Toe</a> (team red)</li>
</ul> </ul>
</body> </body>
</html> </html>

View File

@ -1,10 +1,4 @@
use heapless::Vec; use crate::socket::{HttpRequestType, HttpResCode};
// use pico_website::unwrap;
use crate::{
apps::{self, Content, chat::id_to_static_str},
socket::{HttpRequestType, HttpResCode},
};
use defmt::*;
use super::App; use super::App;
@ -13,138 +7,17 @@ impl App for IndexApp {
fn socket_name(&self) -> &'static str { fn socket_name(&self) -> &'static str {
"index" "index"
} }
async fn handle_request( async fn handle_request<'a>(
&mut self, &'a mut self,
path: &str, path: &str,
_req_type: HttpRequestType, _req_type: HttpRequestType,
_content: &str, _content: &str,
) -> (HttpResCode, &'static str, Option<Content<'_>>) { ) -> (HttpResCode, &'static str, &'a str) {
match path { match path {
"/" | "/index" | "/index.html" => ( "/" | "/index" | "/index.html" => {
HttpResCode::Ok, (HttpResCode::Ok, "html", include_str!("./index.html"))
"html",
#[cfg(debug_assertions)]
Some(include_str!("index.html").into()),
#[cfg(not(debug_assertions))]
Some(include_str!("../../static/index.min.html").into()),
),
"/htmx.js" => (
HttpResCode::Ok,
"javascript",
#[cfg(debug_assertions)]
Some(include_str!("../../static/htmx.js").into()),
#[cfg(not(debug_assertions))]
Some(include_str!("../../static/htmx.min.js").into()),
),
path => {
let (path, args) = path.split_once('?').unwrap_or((path, ""));
let mut team = None;
let mut name = None;
let mut id = None;
for arg in args.split('&') {
match arg.split_once('=') {
Some(("team", "0")) => team = Some("0"),
Some(("team", "1")) => team = Some("1"),
Some(("name", n)) => {
if n.len() >= 1 && n.len() <= 16 {
name = Some(n);
}
}
Some(("id", i)) => {
if let Ok(i) = i.parse::<u8>() {
if i < apps::chat::USERS_LEN {
id = Some(i);
}
}
}
_ => {}
}
}
match path {
"/ttt" => {
let Some(team) = team else {
return (HttpResCode::BadRequest, "", None);
};
#[cfg(debug_assertions)]
let html = include_str!("ttt.html");
#[cfg(not(debug_assertions))]
let html = include_str!("../../static/ttt.min.html");
let mut content = Vec::new();
let r: Result<(), &str> = try {
let (html1, html2) = html.split_once("/ttt.js").ok_or("")?;
content.push(html1)?;
content.push("/ttt.js?team=")?;
content.push(team)?;
content.push(html2)?;
};
unwrap!(r);
(HttpResCode::Ok, "html", Some(Content(content)))
}
"/ttt.js" => {
let Some(team) = team else {
return (HttpResCode::BadRequest, "", None);
};
let mut content = Vec::new();
let r: Result<(), &str> = try {
content.push("const team = ")?;
content.push(team)?;
content.push(";")?;
#[cfg(debug_assertions)]
content.push(include_str!("ttt.js"))?;
#[cfg(not(debug_assertions))]
content.push(include_str!("../../static/ttt.min.js"))?;
};
unwrap!(r);
(HttpResCode::Ok, "javascript", Some(Content(content)))
}
"/chat" => {
let Some(name) = name else {
return (HttpResCode::BadRequest, "", None);
};
// #[cfg(debug_assertions)]
let html = include_str!("chat.html");
// #[cfg(not(debug_assertions))]
// let html = include_str!("../../static/chat.min.html");
let Some(id) = apps::chat::USERNAMES.lock().await.get_id(name) else {
return (HttpResCode::NoContent, "", None);
};
let mut content = Vec::new();
let r: Result<(), &str> = try {
let (html1, html2) = html.split_once("/chat.js").ok_or("")?;
content.push(html1)?;
content.push("/chat.js?id=")?;
content.push(id_to_static_str(id).await)?;
content.push(html2)?;
};
unwrap!(r);
(HttpResCode::Ok, "html", Some(Content(content)))
}
"/chat.js" => {
let Some(id) = id else {
return (HttpResCode::BadRequest, "", None);
};
let mut content = Vec::new();
let r: Result<(), &str> = try {
content.push("const id = ")?;
content.push(id_to_static_str(id).await)?;
content.push(";")?;
// #[cfg(debug_assertions)]
content.push(include_str!("chat.js"))?;
// #[cfg(not(debug_assertions))]
// content.push(include_str!("../../static/chat.min.js"))?;
};
unwrap!(r);
(HttpResCode::Ok, "javascript", Some(Content(content)))
}
_ => (HttpResCode::NotFound, "", None),
}
} }
_ => (HttpResCode::NotFound, "", ""),
} }
} }
} }

View File

@ -1,5 +1,3 @@
use heapless::Vec;
use crate::socket::{HttpRequestType, HttpResCode, ws::Ws}; use crate::socket::{HttpRequestType, HttpResCode, ws::Ws};
#[cfg(feature = "chat")] #[cfg(feature = "chat")]
@ -12,29 +10,19 @@ pub trait App {
fn socket_name(&self) -> &'static str; fn socket_name(&self) -> &'static str;
async fn handle_request<'a>( async fn handle_request<'a>(
&'a mut self, &'a mut self,
_path: &'a str, _path: &str,
_req_type: HttpRequestType, _req_type: HttpRequestType,
_content: &'a str, _content: &str,
) -> (HttpResCode, &'static str, Option<Content<'a>>) { ) -> (HttpResCode, &'static str, &'a str) {
(HttpResCode::NotFound, "", None) (HttpResCode::NotFound, "", "")
} }
fn accept_ws(&self, _path: &str) -> bool { fn accept_ws(&self, _path: &str) -> bool {
false false
} }
async fn handle_ws<const BUF_SIZE: usize>(&mut self, _path: &str, _ws: Ws<'_, BUF_SIZE>) {} async fn handle_ws<'a, const BUF_SIZE: usize, const RES_HEAD_BUF_SIZE: usize>(
} &'a mut self,
_path: &str,
pub struct Content<'a>(pub Vec<&'a str, 8>); _ws: Ws<'a, BUF_SIZE, RES_HEAD_BUF_SIZE>,
) {
impl<'a> From<&'a str> for Content<'a> {
fn from(value: &'a str) -> Self {
let mut v = Vec::new();
v.push(value).unwrap();
Content(v)
}
}
impl Content<'_> {
pub fn len(&self) -> usize {
self.0.iter().fold(0, |acc, s| acc + s.len())
} }
} }

View File

@ -1,32 +1,30 @@
<!doctype html> <!doctype html>
<html> <head>
<head> <script src="./htmx.js"></script>
<style type="text/css"> <style type="text/css">
body { body {
#grid { #grid {
.cell { .cell {
border: 1px dotted black; border: 1px dotted black;
padding: 33%; padding: 33%;
}
.cell[team="0"] {
background-color: dodgerblue;
}
.cell[team="1"] {
background-color: firebrick;
}
display: grid;
border: 1px solid black;
grid-template-rows: 1fr 1fr 1fr;
grid-template-columns: 1fr 1fr 1fr;
} }
display: grid;
border: 1px solid black;
grid-template-rows: 1fr 1fr 1fr;
grid-template-columns: 1fr 1fr 1fr;
} }
</style> }
<script src="/ttt.js" defer></script> </style>
</head> </head>
<html>
<body> <body>
<h1>TicTacToe</h1> <h1>TicTacToe</h1>
<h3 id="team"></h3> <div
<h3 id="winner"></h3> id="game"
<div id="grid"></div> hx-get="/ttt/initial_game"
hx-swap="outerHTML"
hx-trigger="load"
hx-target="this"
></div>
</body> </body>
</html> </html>

View File

@ -1,72 +0,0 @@
//const team = 0;
if (team != 0 && team != 1) {
throw "team is not 0 or 1! team=" + team;
}
const teams = [
{
name: "blue",
color: "dodgerblue",
port: "8080",
},
{
name: "red",
color: "firebrick",
port: "8081",
},
];
document.getElementById("team").innerHTML =
'Team : <span style="color:' +
teams[team].color +
'">' +
teams[team].name +
"</span>";
const ws = new WebSocket(
"ws://192.254.0.2:" + teams[team].port + "/" + teams[team].name,
);
ws.onmessage = (event) => {
if (typeof event.data == "string") {
let msg = JSON.parse(event.data);
let cells = [];
for (let i = 0; i < 9; i++) {
let owner = msg.board[i];
let tagName;
if (msg.turn == team && owner === null) {
tagName = "button";
} else {
tagName = "div";
}
let cell = document.createElement(tagName);
cell.classList.add("cell");
if (tagName === "button") {
cell.addEventListener("click", (event) => {
ws.send(new Uint8Array([i]));
});
}
cell.setAttribute("team", owner);
cells.push(cell);
}
document.getElementById("grid").replaceChildren(...cells);
if (msg.turn == null) {
if (msg.winner == null) {
document.getElementById("winner").innerHTML = "Draw!";
} else {
document.getElementById("winner").innerHTML =
'Winner : <span style="color:' +
teams[msg.winner].color +
'">' +
teams[msg.winner].name +
"</span>";
}
} else {
document.getElementById("winner").innerHTML = "";
}
}
};

View File

@ -1,159 +1,217 @@
use anyhow::Result; use core::fmt::Write;
use core::ops::Not; use core::{ops::Not, sync::atomic::Ordering};
use core::str::from_utf8_unchecked; use embassy_time::{Duration, Instant};
use embassy_sync::blocking_mutex::raw::ThreadModeRawMutex; use heapless::String;
use embassy_sync::mutex::Mutex; use pico_website::unwrap;
use embassy_time::{Duration, Instant, Timer}; use portable_atomic::{AtomicBool, AtomicU32};
// use log::{info, warn};
use defmt::*;
// use pico_website::{unwrap, unwrap_opt};
use serde::Serialize;
use crate::apps::Content;
use crate::socket::ws::{Ws, WsMsg};
use crate::socket::{HttpRequestType, HttpResCode}; use crate::socket::{HttpRequestType, HttpResCode};
use super::App; use super::App;
#[derive(Debug, Serialize, Clone, PartialEq, Eq)] static TURN: AtomicBool = AtomicBool::new(false);
struct Game { // bits [0; 8] : player zero board / bits [9; 17] : player one board
board: [Option<Team>; 9], static BOARD: AtomicU32 = AtomicU32::new(0);
turn: Option<Team>,
winner: Option<Team>,
}
impl Game {
const fn default() -> Self {
Game {
board: [None; 9],
turn: Some(Team::Zero),
winner: None,
}
}
fn check_end(&mut self) -> bool {
for [a, b, c] in [
[0, 1, 2],
[3, 4, 5],
[6, 7, 8],
[0, 3, 6],
[1, 4, 7],
[2, 5, 8],
[0, 4, 8],
[2, 4, 6],
] {
if let Some(t) = self.board[a] {
if self.board[b] == Some(t) && self.board[c] == Some(t) {
self.winner = Some(t);
self.turn = None;
return true;
}
}
}
if self.board.iter().all(|c| c.is_some()) {
self.winner = None;
self.turn = None;
return true;
}
false
}
}
static GAME: Mutex<ThreadModeRawMutex, Game> = Mutex::new(Game::default());
pub struct TttApp { pub struct TttApp {
res_buf: String<2048>,
/// State of the board last time it has been sent
last_board: u32,
team: Team, team: Team,
last_game: Game, end: Option<(Instant, Option<Team>)>,
/// Only one socket manages the end, this can be None even when it's the end
end: Option<Instant>,
json_buf: [u8; 128],
} }
impl TttApp { impl TttApp {
pub fn new(team: Team) -> Self { pub fn new(team: Team) -> Self {
Self { Self {
res_buf: String::new(),
last_board: 0,
team, team,
last_game: Game {
board: [None; 9],
turn: None,
winner: None,
},
end: None, end: None,
json_buf: [0; 128],
} }
} }
pub fn is_ended(&self, board: u32) -> (bool, Option<Team>) {
if let Some((_, t)) = self.end {
return (true, t);
}
for (t, m) in [(Team::Zero, 0), (Team::One, 9)] {
for w in [
0b111000000,
0b000111000,
0b000000111,
0b100100100,
0b010010010,
0b001001001,
0b100010001,
0b001010100,
] {
if board & (w << m) == (w << m) {
return (true, Some(t));
}
}
}
if ((board | (board >> 9)) & 0b111111111) == 0b111111111 {
return (true, None);
}
(false, None)
}
pub fn update_end_state(&mut self, board: &mut u32) {
if let Some((i, _)) = self.end {
if i + Duration::from_secs(7) < Instant::now() {
self.end = None;
BOARD.store(0, Ordering::Release);
*board = 0;
}
} else {
if let (true, t) = self.is_ended(*board) {
self.end = Some((Instant::now(), t));
}
}
}
/// Generate board html
async fn generate_board_res<'a>(
&'a mut self,
board: u32,
turn: Team,
outer_html: bool,
) -> &'a str {
self.res_buf.clear();
if outer_html {
unwrap(self.res_buf.push_str(
"<div \
id=\"game\" \
hx-get=\"/ttt/game\" \
hx-swap=\"innerHTML\" \
hx-trigger=\"every 100ms\" \
hx-target=\"this\"\
>",
))
.await;
}
unwrap(write!(
self.res_buf,
"<h3>Team : <span style=\"color:{}\">{}</span></h3>",
self.team.color(),
self.team.name()
))
.await;
match self.end {
Some((_, Some(t))) => {
unwrap(write!(
self.res_buf,
"<br><h3>Team <span style=\"color:{}\">{}</span> has won!</h3><br>",
t.color(),
t.name()
))
.await
}
Some((_, None)) => unwrap(write!(self.res_buf, "<br><h3>Draw!</h3><br>",)).await,
None => {}
}
unwrap(self.res_buf.push_str("<div id=\"grid\">")).await;
for c in 0..=8 {
let picked_by = if board & (1 << c) != 0 {
Some(Team::Zero)
} else if board & (1 << (9 + c)) != 0 {
Some(Team::One)
} else {
None
};
match picked_by {
Some(t) => {
unwrap(write!(
self.res_buf,
"<div class=\"cell\" style=\"background-color:{}\"></div>",
t.color()
))
.await;
}
None => {
if self.team == turn.into() && self.end.is_none() {
unwrap(write!(
self.res_buf,
"<button class=\"cell\" hx-post=\"/ttt/cell{}\" hx-trigger=\"click\" hx-target=\"#game\" hx-swap=\"innerHTML\"></button>",
c
)).await;
} else {
unwrap(self.res_buf.push_str("<div class=\"cell\"></div>")).await;
}
}
};
}
unwrap(self.res_buf.push_str("</div>")).await;
if outer_html {
unwrap(self.res_buf.push_str("</div>")).await;
}
&self.res_buf
}
} }
impl App for TttApp { impl App for TttApp {
fn socket_name(&self) -> &'static str { fn socket_name(&self) -> &'static str {
match self.team { self.team.name()
Team::Zero => "ttt0",
Team::One => "ttt1",
}
} }
fn accept_ws(&self, path: &str) -> bool { async fn handle_request<'a>(
(self.team == Team::Zero && path == "/blue") || (self.team == Team::One && path == "/red") &'a mut self,
} path: &str,
async fn handle_ws<const BUF_SIZE: usize>(&mut self, _path: &str, mut ws: Ws<'_, BUF_SIZE>) { _req_type: HttpRequestType,
Timer::after_millis(500).await; _content: &str,
let r: Result<()> = try { ) -> (HttpResCode, &'static str, &'a str) {
loop { match path {
Timer::after_millis(1).await; "/" | "/index" | "/index.html" | "/ttt" | "/ttt.html" => {
let Ok(mut game) = GAME.try_lock() else { (HttpResCode::Ok, "html", include_str!("./ttt.html"))
info!("game locked"); }
continue; "/ttt/initial_game" => {
}; let board = BOARD.load(Ordering::Acquire);
if self.last_game != *game { let turn = TURN.load(Ordering::Acquire);
let n = serde_json_core::to_slice(&(*game), &mut self.json_buf).unwrap(); (
let json = unsafe { from_utf8_unchecked(&unwrap!(self.json_buf.get(..n))) }; HttpResCode::Ok,
ws.send(WsMsg::Text(json)).await?; "html",
self.last_game = game.clone(); self.generate_board_res(board, turn.into(), true).await,
} )
if ws.last_msg.elapsed() >= Duration::from_secs(5) { }
ws.send(WsMsg::Ping(&[])).await?; path => {
} if (path.starts_with("/ttt/cell") && path.len() == 10) || path == "/ttt/game" {
if self.end.map(|e| e.elapsed()).unwrap_or_default() > Duration::from_secs(5) { let mut board = BOARD.load(Ordering::Acquire);
self.end = None; let mut turn = TURN.load(Ordering::Acquire);
*game = Game {
turn: Some(!game.winner.unwrap_or_default()), // just return correct board in case of unauthorized move
..Game::default() if path.starts_with("/ttt/cell") && self.team == turn.into() {
}; let clicked_c: Cell = match TryInto::<Cell>::try_into(
} unwrap(path.chars().nth(9).ok_or("no 9th char")).await,
while let Some(r) = ws.rcv().await? { ) {
if let WsMsg::Bytes([c]) = r { Ok(c) => c,
let c = *c as usize; Err(_) => return (HttpResCode::NotFound, "", ""),
if c >= game.board.len() { };
warn!("Cell played is too big!"); if board & ((1 << (clicked_c as u32)) + (1 << (9 + clicked_c as u32))) != 0
continue; {
} return (HttpResCode::Forbidden, "", "");
if game.board[c].is_some() {
warn!("Cell is already taken!");
continue;
}
if game.turn == Some(self.team) {
game.board[c] = Some(self.team);
game.turn = Some(!self.team);
if game.check_end() {
self.end = Some(Instant::now());
}
} else {
warn!("It's not your turn!");
continue;
} }
board = board | (1 << ((self.team as u32 * 9) + clicked_c as u32));
turn = (!self.team).into();
BOARD.store(board, Ordering::Release);
TURN.store(turn, Ordering::Release);
} }
self.update_end_state(&mut board);
if self.last_board != board {
self.last_board = board;
(
HttpResCode::Ok,
"html",
self.generate_board_res(board, turn.into(), false).await,
)
} else {
(HttpResCode::NoContent, "", "")
}
} else {
(HttpResCode::NotFound, "", "")
} }
} }
};
if let Err(e) = r {
warn!(
"Socket {}: error in ws\n{}",
self.socket_name(),
Display2Format(&e)
);
} }
} }
} }
#[derive(Debug, Clone, Copy, PartialEq, Eq, Default)] #[derive(Debug, Clone, Copy, PartialEq, Eq)]
pub enum Team { pub enum Team {
#[default]
Zero = 0, Zero = 0,
One = 1, One = 1,
} }
@ -179,14 +237,6 @@ impl Not for Team {
} }
} }
} }
impl Serialize for Team {
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
where
S: serde::Serializer,
{
serializer.serialize_u8(*self as u8)
}
}
impl Team { impl Team {
fn color(self) -> &'static str { fn color(self) -> &'static str {
match self { match self {

View File

@ -10,9 +10,8 @@ use embassy_net::{
}; };
use embassy_time::Timer; use embassy_time::Timer;
use heapless::Vec; use heapless::Vec;
// use log::{info, warn}; use log::{info, warn};
use defmt::*; use pico_website::unwrap;
// use pico_website::{unwrap, unwrap_opt};
#[embassy_executor::task(pool_size = 1)] #[embassy_executor::task(pool_size = 1)]
pub async fn dhcp_server(stack: Stack<'static>) { pub async fn dhcp_server(stack: Stack<'static>) {
@ -33,33 +32,28 @@ pub async fn dhcp_server(stack: Stack<'static>) {
&mut tx_meta, &mut tx_meta,
&mut tx_buffer, &mut tx_buffer,
); );
unwrap!(socket.bind(67)); unwrap(socket.bind(67)).await;
info!("Starting DHCP server"); info!("Starting DHCP server");
loop { loop {
Timer::after_secs(0).await; let (n, _) = unwrap(socket.recv_from(&mut buf).await).await;
let (n, _) = unwrap!(socket.recv_from(&mut buf).await);
let msg = unwrap!(buf.get(..n)); let msg = unwrap(dhcpv4::Message::new(&buf[..n])).await;
let msg = dhcpv4::Message::new(&msg).unwrap();
let msg_type = v4_options!(msg; MessageType required).unwrap(); let msg_type = unwrap(v4_options!(msg; MessageType required)).await;
let mut rapid_commit = false; let mut rapid_commit = false;
if msg if unwrap(msg.options())
.options() .await
.unwrap()
.any(|opt| matches!(opt, Ok((DhcpOption::Unknown(80, _), _)))) .any(|opt| matches!(opt, Ok((DhcpOption::Unknown(80, _), _))))
{ {
if msg_type != DhcpMsgType::DISCOVER { if msg_type != DhcpMsgType::DISCOVER {
warn!( warn!("WARN : dhcp rapid commit option on {:?} message", msg_type);
"WARN : dhcp rapid commit option on {:?} message",
Debug2Format(&msg_type)
);
continue 'listen; continue 'listen;
} }
rapid_commit = true; rapid_commit = true;
} }
info!("Dhcp: received {:?} message", Debug2Format(&msg_type)); info!("Dhcp: received {:?} message", msg_type);
Timer::after_secs(0).await;
match msg_type { match msg_type {
DhcpMsgType::DISCOVER | DhcpMsgType::REQUEST => { DhcpMsgType::DISCOVER | DhcpMsgType::REQUEST => {
@ -94,8 +88,8 @@ pub async fn dhcp_server(stack: Stack<'static>) {
opts.clear(); opts.clear();
opts.extend_from_slice( opts.extend_from_slice(
v4_options!(msg; ParameterRequestList) unwrap(v4_options!(msg; ParameterRequestList))
.unwrap() .await
.unwrap_or(&[]), .unwrap_or(&[]),
) )
.unwrap(); .unwrap();
@ -104,7 +98,7 @@ pub async fn dhcp_server(stack: Stack<'static>) {
(DhcpMsgType::DISCOVER, false) => &[54], (DhcpMsgType::DISCOVER, false) => &[54],
(DhcpMsgType::DISCOVER, true) => &[54, 80], (DhcpMsgType::DISCOVER, true) => &[54, 80],
(DhcpMsgType::REQUEST, false) => &[1, 3, 51, 6, 54], (DhcpMsgType::REQUEST, false) => &[1, 3, 51, 6, 54],
_ => defmt::unreachable!(), _ => unreachable!(),
}; };
for o in default_opts { for o in default_opts {
if !opts.contains(o) { if !opts.contains(o) {
@ -112,10 +106,10 @@ pub async fn dhcp_server(stack: Stack<'static>) {
} }
} }
unwrap!(write_dhcp_opts(&mut res_buf, &opts)); unwrap(write_dhcp_opts(&mut res_buf, &opts).await).await;
res_buf.push(255).unwrap(); // end option res_buf.push(255).unwrap(); // end option
unwrap!( unwrap(
socket socket
.send_to( .send_to(
&res_buf, &res_buf,
@ -129,8 +123,10 @@ pub async fn dhcp_server(stack: Stack<'static>) {
}, },
) )
.await, .await,
); )
.await;
info!("Dhcp: offer/ack sent for ip 192.254.0.{}", current_ip); info!("Dhcp: offer/ack sent for ip 192.254.0.{}", current_ip);
Timer::after_secs(0).await;
if msg_type == DhcpMsgType::REQUEST || rapid_commit { if msg_type == DhcpMsgType::REQUEST || rapid_commit {
current_ip += 1; current_ip += 1;
@ -147,7 +143,7 @@ pub async fn dhcp_server(stack: Stack<'static>) {
} }
} }
fn write_dhcp_opts<const N: usize>(buf: &mut Vec<u8, N>, op_codes: &[u8]) -> Result<(), ()> { async fn write_dhcp_opts<const N: usize>(buf: &mut Vec<u8, N>, op_codes: &[u8]) -> Result<(), ()> {
for o in op_codes { for o in op_codes {
let (opt_len, opt): (u8, &[u8]) = match o { let (opt_len, opt): (u8, &[u8]) = match o {
1 => (4, &[255, 255, 255, 0]), // DhcpOption::SubnetMask(&dhcpv4::Addr([255, 255, 255, 0])), 1 => (4, &[255, 255, 255, 0]), // DhcpOption::SubnetMask(&dhcpv4::Addr([255, 255, 255, 0])),
@ -164,7 +160,8 @@ fn write_dhcp_opts<const N: usize>(buf: &mut Vec<u8, N>, op_codes: &[u8]) -> Res
59 => (4, &3500_u32.to_be_bytes()), // rebinding time 59 => (4, &3500_u32.to_be_bytes()), // rebinding time
80 => (0, &[]), 80 => (0, &[]),
_ => { _ => {
warn!("Dhcp: unhandled requested option {}", o); info!("Dhcp: unhandled requested option {}", o);
Timer::after_secs(0).await;
continue; continue;
} }
}; };

View File

@ -4,9 +4,8 @@ use embassy_net::{
udp::{PacketMetadata, UdpSocket}, udp::{PacketMetadata, UdpSocket},
}; };
use embassy_time::Timer; use embassy_time::Timer;
// use log::{info, warn}; use log::{info, warn};
use defmt::*; use pico_website::unwrap;
// use pico_website::{unwrap, unwrap_opt};
#[embassy_executor::task(pool_size = 1)] #[embassy_executor::task(pool_size = 1)]
pub async fn dns_server(stack: Stack<'static>) { pub async fn dns_server(stack: Stack<'static>) {
@ -24,21 +23,17 @@ pub async fn dns_server(stack: Stack<'static>) {
&mut tx_meta, &mut tx_meta,
&mut tx_buffer, &mut tx_buffer,
); );
unwrap!(socket.bind(53)); unwrap(socket.bind(53)).await;
info!("Starting DNS server"); info!("Starting DNS server");
loop { loop {
Timer::after_secs(0).await; Timer::after_secs(0).await;
let (n, meta) = unwrap!(socket.recv_from(&mut buf).await); let (n, meta) = unwrap(socket.recv_from(&mut buf).await).await;
let msg = unwrap!(buf.get_mut(..n)); let msg = match dnsparse::Message::parse(&mut buf[..n]) {
let msg = match dnsparse::Message::parse(msg) {
Ok(msg) => msg, Ok(msg) => msg,
Err(e) => { Err(e) => {
warn!( warn!("Dns: Error while parsing DNS message : {:#?}", e);
"Dns: Error while parsing DNS message : {}",
Display2Format(&e)
);
continue; continue;
} }
}; };
@ -46,7 +41,7 @@ pub async fn dns_server(stack: Stack<'static>) {
if msg.header().opcode() != OpCode::Query { if msg.header().opcode() != OpCode::Query {
info!( info!(
"Dns: Received unknown dns opcode ({:?}), ignoring", "Dns: Received unknown dns opcode ({:?}), ignoring",
Debug2Format(&msg.header().opcode()) msg.header().opcode()
); );
continue; continue;
} }
@ -73,9 +68,9 @@ pub async fn dns_server(stack: Stack<'static>) {
ttl: 600, ttl: 600,
rdata: &[192, 254, 0, 2], rdata: &[192, 254, 0, 2],
}); });
info!("Dns: Giving {}", Display2Format(&q.name())); info!("Dns: Giving {}", q.name());
} else { } else {
info!("Dns: Unknown uri, ignoring ({})", Display2Format(&q.name())); info!("Dns: Unknown uri, ignoring ({})", q.name());
} }
} }
_ => { _ => {

View File

@ -1,42 +1,18 @@
#![no_std] #![no_std]
use core::{fmt::Debug, panic::PanicInfo}; use core::fmt::Debug;
use embassy_time::Timer; use embassy_time::Timer;
// use log::error; use log::info;
pub async fn unwrap<T, E: Debug>(res: Result<T, E>) -> T { pub async fn unwrap<T, E: Debug>(res: Result<T, E>) -> T {
match res { match res {
Ok(v) => v, Ok(v) => v,
Err(e) => loop { Err(e) => {
// error!("FATAL ERROR : {:?}", e); info!("FATAL ERROR : {:?}", e);
Timer::after_secs(5).await; loop {
}, info!("FATAL ERROR : {:?}", e);
Timer::after_secs(5).await;
}
}
} }
} }
pub async fn unwrap_opt<T>(opt: Option<T>) -> T {
expect_opt("option unwraped", opt).await
}
pub async fn assert(condition: bool) {
if !condition {
let err: Result<(), &str> = Err("assert failed");
unwrap(err).await;
}
}
pub async fn expect_opt<T>(msg: &str, opt: Option<T>) -> T {
unwrap(opt.ok_or(msg)).await
}
pub async fn unimplemented() -> ! {
let err: Result<(), &str> = Err("unimplemented");
unwrap(err).await;
loop {}
}
// // TODO: make this log work
// #[panic_handler]
// fn panic(info: &PanicInfo) -> ! {
// // error!("PANIC: {}", info);
// loop {}
// }

View File

@ -4,30 +4,26 @@
#![feature(impl_trait_in_assoc_type)] #![feature(impl_trait_in_assoc_type)]
#![feature(slice_split_once)] #![feature(slice_split_once)]
#![feature(try_blocks)] #![feature(try_blocks)]
#![feature(impl_trait_in_bindings)]
#![feature(array_repeat)]
#![feature(async_iterator)]
use core::mem::MaybeUninit;
#[cfg(feature = "wifi-connect")] #[cfg(feature = "wifi-connect")]
use core::net::Ipv4Addr; use core::net::Ipv4Addr;
use cyw43_pio::{DEFAULT_CLOCK_DIVIDER, PioSpi}; use cyw43_pio::{DEFAULT_CLOCK_DIVIDER, PioSpi};
use defmt::*;
use embassy_executor::Spawner; use embassy_executor::Spawner;
use embassy_net::{Config, StackResources}; use embassy_net::{Config, StackResources};
use embassy_rp::bind_interrupts; use embassy_rp::bind_interrupts;
use embassy_rp::clocks::RoscRng; use embassy_rp::clocks::RoscRng;
use embassy_rp::gpio::{Level, Output}; use embassy_rp::gpio::{Level, Output};
use embassy_rp::peripherals::USB;
use embassy_rp::peripherals::{DMA_CH0, PIO0}; use embassy_rp::peripherals::{DMA_CH0, PIO0};
use embassy_rp::pio::{InterruptHandler as PioInterruptHandler, Pio}; use embassy_rp::pio::{InterruptHandler as PioInterruptHandler, Pio};
use embedded_alloc::LlffHeap as Heap; use embassy_rp::usb::{Driver, InterruptHandler as UsbInterruptHandler};
use log::info;
use pico_website::unwrap;
use rand_core::RngCore;
use static_cell::StaticCell; use static_cell::StaticCell;
use {defmt_rtt as _, panic_probe as _}; use {defmt_rtt as _, panic_probe as _};
#[global_allocator]
static HEAP: Heap = Heap::empty();
#[cfg(feature = "dhcp")] #[cfg(feature = "dhcp")]
mod dhcp; mod dhcp;
@ -38,14 +34,14 @@ mod apps;
mod socket; mod socket;
bind_interrupts!(struct Irqs { bind_interrupts!(struct Irqs {
// USBCTRL_IRQ => UsbInterruptHandler<USB>; USBCTRL_IRQ => UsbInterruptHandler<USB>;
PIO0_IRQ_0 => PioInterruptHandler<PIO0>; PIO0_IRQ_0 => PioInterruptHandler<PIO0>;
}); });
// #[embassy_executor::task] #[embassy_executor::task]
// async fn logger_task(driver: Driver<'static, USB>) { async fn logger_task(driver: Driver<'static, USB>) {
// embassy_usb_logger::run!(1024, log::LevelFilter::Info, driver); embassy_usb_logger::run!(1024, log::LevelFilter::Info, driver);
// } }
#[embassy_executor::task] #[embassy_executor::task]
async fn cyw43_task( async fn cyw43_task(
@ -61,23 +57,18 @@ async fn net_task(mut runner: embassy_net::Runner<'static, cyw43::NetDriver<'sta
#[embassy_executor::main] #[embassy_executor::main]
async fn main(spawner: Spawner) { async fn main(spawner: Spawner) {
// Init heap
// const HEAP_SIZE: usize = 4096;
// static mut HEAP_MEM: [MaybeUninit<u8>; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE];
// let heap: Heap = Heap::empty();
// unsafe { heap.init(&raw mut HEAP_MEM as usize, HEAP_SIZE) }
{
use core::mem::MaybeUninit;
const HEAP_SIZE: usize = 1024;
static mut HEAP_MEM: [MaybeUninit<u8>; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE];
unsafe { HEAP.init(&raw mut HEAP_MEM as usize, HEAP_SIZE) }
}
let p = embassy_rp::init(Default::default()); let p = embassy_rp::init(Default::default());
// let driver = Driver::new(p.USB, Irqs); let driver = Driver::new(p.USB, Irqs);
// spawner.spawn(logger_task(driver)).unwrap(); spawner.spawn(logger_task(driver)).unwrap();
let mut rng = RoscRng; let mut rng = RoscRng;
// let mut i = 0;
// loop {
// info!("test{}", i);
// Timer::after_secs(1).await;
// i += 1;
// }
let fw = include_bytes!("../cyw43-firmware/43439A0.bin"); let fw = include_bytes!("../cyw43-firmware/43439A0.bin");
let clm = include_bytes!("../cyw43-firmware/43439A0_clm.bin"); let clm = include_bytes!("../cyw43-firmware/43439A0_clm.bin");
let pwr = Output::new(p.PIN_23, Level::Low); let pwr = Output::new(p.PIN_23, Level::Low);
@ -97,7 +88,7 @@ async fn main(spawner: Spawner) {
static STATE: StaticCell<cyw43::State> = StaticCell::new(); static STATE: StaticCell<cyw43::State> = StaticCell::new();
let state = STATE.init(cyw43::State::new()); let state = STATE.init(cyw43::State::new());
let (net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await; let (net_device, mut control, runner) = cyw43::new(state, pwr, spi, fw).await;
unwrap!(spawner.spawn(cyw43_task(runner))); unwrap(spawner.spawn(cyw43_task(runner))).await;
control.init(clm).await; control.init(clm).await;
control control
@ -144,7 +135,7 @@ async fn main(spawner: Spawner) {
seed, seed,
); );
unwrap!(spawner.spawn(net_task(runner))); unwrap(spawner.spawn(net_task(runner))).await;
#[cfg(not(feature = "wifi-connect"))] #[cfg(not(feature = "wifi-connect"))]
control.start_ap_open("pico", 5).await; control.start_ap_open("pico", 5).await;
@ -172,28 +163,33 @@ async fn main(spawner: Spawner) {
// Wait for DHCP, not necessary when using static IP // Wait for DHCP, not necessary when using static IP
info!("waiting for DHCP..."); info!("waiting for DHCP...");
stack.wait_config_up().await; stack.wait_config_up().await;
// while !stack.is_config_up() {
// Timer::after_millis(100).await;
// }
info!("DHCP is now up!"); info!("DHCP is now up!");
info!( info!(
"ip : {}", "ip : {}",
unwrap!(stack.config_v4().ok_or("no dhcp config")).address unwrap(stack.config_v4().ok_or("no dhcp config"))
.await
.address
) )
} }
#[cfg(feature = "dhcp")] #[cfg(feature = "dhcp")]
unwrap!(spawner.spawn(dhcp::dhcp_server(stack))); unwrap(spawner.spawn(dhcp::dhcp_server(stack))).await;
#[cfg(feature = "dns")] #[cfg(feature = "dns")]
unwrap!(spawner.spawn(dns::dns_server(stack))); unwrap(spawner.spawn(dns::dns_server(stack))).await;
unwrap!(spawner.spawn(socket::index_listen_task(stack, 80))); unwrap(spawner.spawn(socket::index_listen_task(stack, 80))).await;
#[cfg(feature = "ttt")] #[cfg(feature = "ttt")]
{ {
unwrap!(spawner.spawn(socket::ttt_listen_task(stack, apps::ttt::Team::Zero, 8080))); unwrap(spawner.spawn(socket::ttt_listen_task(stack, apps::ttt::Team::Zero, 8080))).await;
unwrap!(spawner.spawn(socket::ttt_listen_task(stack, apps::ttt::Team::One, 8081))); unwrap(spawner.spawn(socket::ttt_listen_task(stack, apps::ttt::Team::One, 8081))).await;
} }
#[cfg(feature = "chat")] #[cfg(feature = "chat")]
for i in 0..4 { for _ in 0..4 {
unwrap!(spawner.spawn(socket::chat_listen_task(stack, i, 9000 + i as u16))); unwrap(spawner.spawn(socket::chat_listen_task(stack, 8082))).await;
} }
info!("All apps lauched!"); info!("All apps lauched!");
} }

View File

@ -1,20 +1,13 @@
use anyhow::{Result, anyhow}; use base64::{EncodeSliceError, prelude::*};
use base64::prelude::*;
use core::fmt::Write;
use core::str::from_utf8; use core::str::from_utf8;
use core::write; use core::{fmt::Write, str::FromStr};
use defmt::*;
use embassy_net::tcp::TcpSocket; use embassy_net::tcp::TcpSocket;
use embassy_time::{Duration, Timer}; use embassy_time::{Duration, Timer};
use embedded_io_async::Write as _; use embedded_io_async::Write as _;
use heapless::{String, Vec}; use heapless::{String, Vec};
// use log::{info, warn}; use log::{info, warn};
// use pico_website::unwrap;
use sha1::{Digest, Sha1}; use sha1::{Digest, Sha1};
use crate::apps::Content;
use crate::{apps, socket::ws::Ws}; use crate::{apps, socket::ws::Ws};
pub mod ws; pub mod ws;
@ -22,38 +15,33 @@ pub mod ws;
#[cfg(feature = "ttt")] #[cfg(feature = "ttt")]
#[embassy_executor::task(pool_size = 2)] #[embassy_executor::task(pool_size = 2)]
pub async fn ttt_listen_task(stack: embassy_net::Stack<'static>, team: apps::ttt::Team, port: u16) { pub async fn ttt_listen_task(stack: embassy_net::Stack<'static>, team: apps::ttt::Team, port: u16) {
listen_task::<32, 32, 1024, 256>(stack, apps::ttt::TttApp::new(team), port).await listen_task(stack, apps::ttt::TttApp::new(team), port).await
} }
#[embassy_executor::task(pool_size = 2)] #[embassy_executor::task(pool_size = 2)]
pub async fn index_listen_task(stack: embassy_net::Stack<'static>, port: u16) { pub async fn index_listen_task(stack: embassy_net::Stack<'static>, port: u16) {
listen_task::<64, 0, 2048, 1024>(stack, apps::index::IndexApp, port).await listen_task(stack, apps::index::IndexApp, port).await
} }
#[cfg(feature = "chat")] #[cfg(feature = "chat")]
#[embassy_executor::task(pool_size = 4)] #[embassy_executor::task(pool_size = 4)]
pub async fn chat_listen_task(stack: embassy_net::Stack<'static>, id: u8, port: u16) { pub async fn chat_listen_task(stack: embassy_net::Stack<'static>, port: u16) {
listen_task::<64, 1024, 1024, 1024>(stack, apps::chat::ChatApp::new(id), port).await listen_task(stack, apps::chat::ChatApp::new(), port).await
} }
pub async fn listen_task< pub async fn listen_task(stack: embassy_net::Stack<'static>, mut app: impl apps::App, port: u16) {
const PATH_LEN: usize, // loop {
const BUF_LEN: usize, // info!("team:{:?}", team);
const RX_LEN: usize, // Timer::after_millis(0).await;
const TX_LEN: usize, // }
>( let mut rx_buffer = [0; 1024];
stack: embassy_net::Stack<'static>, let mut tx_buffer = [0; 2048];
mut app: impl apps::App, let mut buf = [0; 1024];
port: u16,
) {
let mut rx_buffer = [0; RX_LEN];
let mut tx_buffer = [0; TX_LEN];
let mut head_buf = Vec::<u8, 256>::new(); let mut head_buf = Vec::<u8, 256>::new();
loop { loop {
Timer::after_secs(0).await; Timer::after_secs(0).await;
let mut socket = TcpSocket::new(stack, &mut rx_buffer, &mut tx_buffer); let mut socket = TcpSocket::new(stack, &mut rx_buffer, &mut tx_buffer);
// socket.set_timeout(Some(Duration::from_secs(5))); socket.set_timeout(Some(Duration::from_secs(30)));
// socket.set_keep_alive(Some(Duration::from_secs(1)));
info!("Socket {}: Listening on TCP:{}...", app.socket_name(), port); info!("Socket {}: Listening on TCP:{}...", app.socket_name(), port);
if let Err(e) = socket.accept(port).await { if let Err(e) = socket.accept(port).await {
@ -67,153 +55,155 @@ pub async fn listen_task<
socket.remote_endpoint() socket.remote_endpoint()
); );
// let (mut rx, mut tx) = socket.split(); loop {
let mut buf = String::<BUF_LEN>::new();
let mut path = String::<PATH_LEN>::new();
let mut request_type = HttpRequestType::Get;
let mut is_ws = false;
let r: Result<&str> = 'connection: loop {
Timer::after_secs(0).await; Timer::after_secs(0).await;
let n = match socket.read(&mut buf).await {
match socket Ok(0) => {
.read_with(|msg| { warn!("read EOF");
let (headers, content) = match from_utf8(msg) { break;
Ok(b) => match b.split_once("\r\n\r\n") { }
Some(t) => t, Ok(n) => n,
None => (b, ""),
},
Err(e) => {
return (0, Err(e.into()));
}
};
buf.clear();
if buf.push_str(content).is_err() {
return (
0,
Err(anyhow!("Received content is bigger than maximum content!")),
);
}
let mut hl = headers.lines();
match hl.next() {
None => {
return (0, Err(anyhow!("Empty request")));
}
Some(l1) => {
let mut l1 = l1.split(' ');
request_type = match l1.next() {
Some("GET") => HttpRequestType::Get,
Some("POST") => HttpRequestType::Post,
Some(t) => {
return (0, Err(anyhow!("Unknown request type : {}", t)));
}
None => {
return (0, Err(anyhow!("No request type")));
}
};
path.clear();
if let Err(_) = path.push_str(match l1.next() {
Some(path) => path,
None => {
return (0, Err(anyhow!("No path")));
}
}) {
return (0, Err(anyhow!("Path is too big!")));
}
}
};
let mut host = None;
let mut ws_key = None;
for h in hl {
let Some((name, val)) = h.split_once(':') else {
continue;
};
let name = name.trim();
let val = val.trim();
match (name, val) {
("Host", _) => host = Some(val),
("Upgrade", "websocket") => is_ws = true,
("Sec-WebSocket-Key", _) => ws_key = Some(val),
_ => {}
}
}
let Some(host) = host else {
return (0, Err(anyhow!("No host!")));
};
info!(
"Socket {}: {:?}{} request for {}{}",
app.socket_name(),
request_type,
if is_ws { " websocket" } else { "" },
host,
path,
);
buf.clear();
if is_ws {
let Some(key) = ws_key else {
return (0, Err(anyhow!("No ws key!")));
};
if buf.push_str(key).is_err() {
return (0, Err(anyhow!("Ws key is too long!")));
}
} else {
if buf.push_str(content).is_err() {
return (0, Err(anyhow!("Content is too long!")));
}
}
(msg.len(), Ok(()))
})
.await
{
Ok(Ok(())) => {}
Ok(Err(e)) => break 'connection Err(e),
Err(e) => { Err(e) => {
break 'connection Ok("connection reset"); warn!("Socket {}: read error: {:?}", app.socket_name(), e);
break;
}
};
head_buf.clear();
let (headers, content) = match from_utf8(&buf[..n]) {
Ok(b) => match b.split_once("\r\n\r\n") {
Some(t) => t,
None => (b, ""),
},
Err(_) => {
warn!("Non utf8 http request");
break;
} }
}; };
info!("\n{:?}\n", headers);
let mut hl = headers.lines();
let (request_type, path) = match hl.next() {
None => {
warn!("Empty request");
break;
}
Some(l1) => {
let mut l1 = l1.split(' ');
(
match l1.next() {
Some("GET") => HttpRequestType::Get,
Some("POST") => HttpRequestType::Post,
Some(t) => {
warn!("Unknown request type : {}", t);
break;
}
None => {
warn!("No request type");
break;
}
},
match l1.next() {
Some(path) => path,
None => {
warn!("No path");
break;
}
},
)
}
};
let mut host = None;
let mut ws_handshake = false;
let mut ws_key = None;
for h in hl {
let Some((name, val)) = h.split_once(':') else {
continue;
};
let name = name.trim();
let val = val.trim();
match (name, val) {
("Host", _) => host = Some(val),
("Upgrade", "websocket") => ws_handshake = true,
("Sec-WebSocket-Key", _) => ws_key = Some(val),
_ => {}
}
}
let Some(host) = host else {
warn!("No host");
break;
};
info!(
"Socket {}: {:?}{} request for {}{}",
app.socket_name(),
request_type,
if ws_handshake { " websocket" } else { "" },
host,
path,
);
Timer::after_secs(0).await;
head_buf.clear(); head_buf.clear();
let res_content: Result<Option<Content>, core::fmt::Error> = try { let res_content: Result<&str, core::fmt::Error> = try {
if is_ws { if ws_handshake {
if !app.accept_ws(&path) { if !app.accept_ws(path) {
warn!(
"Socket {}: client tried to access unknown ws path : {}",
app.socket_name(),
path
);
write!( write!(
&mut head_buf, &mut head_buf,
"{}\r\n\r\n", "{}\r\n\r\n",
Into::<&str>::into(HttpResCode::NotFound) Into::<&str>::into(HttpResCode::NotFound)
)?; )?;
None ""
} else { } else {
let accept = compute_ws_accept(&buf); if path.len() > 16 {
warn!("Ws socket cannot have path longer than 16 chars!");
break;
}
let Some(key) = ws_key else {
warn!("No ws key!");
break;
};
let accept = match compute_ws_accept(key).await {
Ok(a) => a,
Err(e) => {
warn!("compute ws accept error : {:?}", e);
break;
}
};
write!( write!(
&mut head_buf, &mut head_buf,
"{}\r\n\ "{}\r\n\
Upgrade: websocket\r\n\ Upgrade: websocket\r\n\
Connection: Upgrade\r\n\ Connection: Upgrade\r\n\
Sec-WebSocket-Accept: {}\r\n\r\n", Sec-WebSocket-Accept: {}\r\n\r\n",
// Sec-WebSocket-Protocol: chat\r\n
Into::<&str>::into(HttpResCode::SwitchingProtocols), Into::<&str>::into(HttpResCode::SwitchingProtocols),
accept accept
)?; )?;
None ""
} }
} else { } else {
let (code, res_type, res_content) = let (code, res_type, res_content): (HttpResCode, &str, &str) = match path {
app.handle_request(&path, request_type, &buf).await; "/htmx.js" => (
HttpResCode::Ok,
"javascript",
#[cfg(debug_assertions)]
include_str!("../static/htmx.js"),
#[cfg(not(debug_assertions))]
include_bytes!("../static/htmx.min.js"),
),
_ => app.handle_request(path, request_type, content).await,
};
write!(&mut head_buf, "{}", Into::<&str>::into(code))?; write!(&mut head_buf, "{}", Into::<&str>::into(code))?;
if let Some(ref c) = res_content { if res_type.len() > 0 {
write!( write!(
&mut head_buf, &mut head_buf,
"\r\n\ "\r\n\
Content-Type: text/{}\r\n\ Content-Type: text/{}\r\n\
Content-Length: {}\r\n\ Content-Length: {}\r\n",
Connection: close\r\n",
res_type, res_type,
c.len() res_content.len()
)?; )?;
} }
write!(&mut head_buf, "\r\n\r\n")?; write!(&mut head_buf, "\r\n\r\n")?;
@ -224,59 +214,42 @@ pub async fn listen_task<
let res_content = match res_content { let res_content = match res_content {
Ok(rc) => rc, Ok(rc) => rc,
Err(e) => { Err(e) => {
break 'connection Err(anyhow!("Res buffer write error : {:?}", e)); warn!("res buffer write error: {:?}", e);
break;
} }
}; };
let w: Result<(), embassy_net::tcp::Error> = try { info!("\n{}\n", from_utf8(&head_buf).unwrap());
socket.write_all(&head_buf).await?;
if let Some(ref c) = res_content { match socket.write_all(&head_buf).await {
for s in c.0.iter() { Ok(()) => {}
socket.write_all(s.as_bytes()).await?; Err(e) => {
} warn!("write error: {:?}", e);
break;
}
};
match socket.write_all(res_content.as_bytes()).await {
Ok(()) => {}
Err(e) => {
warn!("write error: {:?}", e);
break;
} }
}; };
if let Err(_) = w { if ws_handshake {
break 'connection Ok("connection reset"); let path: String<16> = String::from_str(path).unwrap();
}; app.handle_ws(
&path,
if is_ws { Ws::new(&mut socket, &mut buf, &mut head_buf, app.socket_name()),
break 'connection Ok(""); )
.await;
break;
} }
};
match r {
Ok("") => {
info!("Socket {}: Closing connection", app.socket_name());
}
Ok(msg) => {
info!("Socket {}: Closing connection ({})", app.socket_name(), msg);
}
Err(e) => {
warn!(
"Socket {}: Closing connection ({})",
app.socket_name(),
Display2Format(&e)
);
}
}
if is_ws {
let mut buf = buf.into_bytes();
buf.resize_default(BUF_LEN).unwrap();
app.handle_ws::<BUF_LEN>(
&path,
Ws::new(
&mut socket,
&mut buf.into_array().unwrap(),
app.socket_name(),
),
)
.await;
} }
} }
} }
#[derive(Clone, Copy, Debug, Format)] #[derive(Clone, Copy, Debug)]
pub enum HttpRequestType { pub enum HttpRequestType {
Get, Get,
Post, Post,
@ -312,13 +285,13 @@ impl Into<&str> for HttpResCode {
} }
} }
fn compute_ws_accept(key: &str) -> String<28> { async fn compute_ws_accept(key: &str) -> Result<String<28>, EncodeSliceError> {
let mut res = Vec::<u8, 28>::new(); let mut res = Vec::<u8, 28>::new();
res.resize_default(28).unwrap(); res.extend_from_slice(&[0; 28]).unwrap();
let mut hasher = Sha1::new(); let mut hasher = Sha1::new();
hasher.update(key.as_bytes()); hasher.update(key.as_bytes());
hasher.update(b"258EAFA5-E914-47DA-95CA-C5AB0DC85B11"); hasher.update(b"258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
let hash = hasher.finalize(); let hash = hasher.finalize();
BASE64_STANDARD.encode_slice(hash, &mut res).unwrap(); BASE64_STANDARD.encode_slice(hash, &mut res)?;
String::from_utf8(res).unwrap() Ok(String::from_utf8(res).unwrap())
} }

View File

@ -1,14 +1,12 @@
use core::str::from_utf8; use core::str::from_utf8;
use anyhow::{Result, anyhow};
use embassy_net::tcp::{TcpReader, TcpSocket, TcpWriter}; use embassy_net::tcp::{TcpReader, TcpSocket, TcpWriter};
use embassy_time::Instant; use embassy_time::Instant;
use embedded_io_async::ReadReady; use embedded_io_async::{ErrorType, ReadReady, Write};
// use log::warn; use heapless::Vec;
use defmt::*; use log::{info, warn};
// use pico_website::{assert, unwrap, unwrap_opt};
#[derive(Clone, Copy, Debug, Format)] #[derive(Clone, Copy)]
pub enum WsMsg<'a> { pub enum WsMsg<'a> {
Ping(&'a [u8]), Ping(&'a [u8]),
Pong(&'a [u8]), Pong(&'a [u8]),
@ -17,10 +15,6 @@ pub enum WsMsg<'a> {
Unknown(u8, &'a [u8]), Unknown(u8, &'a [u8]),
} }
impl WsMsg<'_> { impl WsMsg<'_> {
const TEXT: u8 = 1;
const BYTES: u8 = 2;
const PING: u8 = 9;
const PONG: u8 = 10;
pub const fn len(&self) -> usize { pub const fn len(&self) -> usize {
self.as_bytes().len() self.as_bytes().len()
} }
@ -44,196 +38,136 @@ impl WsMsg<'_> {
struct WsRx<'a, const BUF_SIZE: usize> { struct WsRx<'a, const BUF_SIZE: usize> {
socket: TcpReader<'a>, socket: TcpReader<'a>,
buf: &'a mut [u8; BUF_SIZE], buf: &'a mut [u8; BUF_SIZE],
msg_in_buf: Option<(usize, usize)>, // (start, length) last_msg: Instant,
} }
struct WsTx<'a> { struct WsTx<'a, const HEAD_BUF_SIZE: usize> {
socket: TcpWriter<'a>, socket: TcpWriter<'a>,
head_buf: &'a mut Vec<u8, HEAD_BUF_SIZE>,
} }
impl<'a> WsTx<'a> { impl<'a, const HEAD_BUF_SIZE: usize> WsTx<'a, HEAD_BUF_SIZE> {
pub async fn send_with<F: Fn(&mut [u8]) -> Result<usize>>( pub async fn send<'m>(&mut self, msg: WsMsg<'m>) -> Result<(), ()> {
&mut self, self.head_buf.clear();
msg_code: u8, self.head_buf.push(0b1000_0000 | msg.code()).unwrap();
f: F, if msg.len() < 126 {
) -> Result<()> { self.head_buf.push(msg.len() as u8).unwrap();
if self.send_with_no_flush(msg_code, &f).await.is_err() {
self.socket
.flush()
.await
.map_err(|_| anyhow!("connection reset"))?;
self.send_with_no_flush(msg_code, f).await
} else { } else {
Ok(()) self.head_buf.push(0b0111_1110).unwrap();
self.head_buf
.extend_from_slice(&(msg.len() as u16).to_le_bytes())
.unwrap();
self.head_buf.extend_from_slice(msg.as_bytes()).unwrap();
} }
} let w: Result<(), <TcpSocket<'_> as ErrorType>::Error> = try {
pub async fn send_with_no_flush<F: FnOnce(&mut [u8]) -> Result<usize>>( self.socket.write_all(&self.head_buf).await?;
&mut self, self.socket.write_all(msg.as_bytes()).await?;
msg_code: u8, };
f: F, w.map_err(|e| {
) -> Result<()> { warn!("write error: {:?}", e);
self.socket ()
.write_with(|buf| {
if buf.len() < 6 {
return (0, Err(anyhow!("buffer too small")));
}
buf[0] = 0b1000_0000 | msg_code;
let n = match f(&mut buf[4..]) {
Ok(n) => n,
Err(e) => return (0, Err(e)),
};
if n < 126 {
buf[1] = n as u8;
buf.copy_within(4..4 + n, 2);
(n + 2, Ok(()))
} else {
buf[1..=2].copy_from_slice(&(n as u16).to_le_bytes());
(n + 4, Ok(()))
}
})
.await
.map_err(|_| anyhow!("connection reset"))?
}
pub async fn send<'m>(&mut self, msg: WsMsg<'m>) -> Result<()> {
self.send_with(msg.code(), |buf| {
let msg = msg.as_bytes();
if buf.len() < msg.len() {
Err(anyhow!("buffer smaller than message"))
} else {
buf[..msg.len()].copy_from_slice(msg);
Ok(msg.len())
}
}) })
.await
}
pub async fn send_json<T: serde::Serialize>(&mut self, msg: &T) -> Result<()> {
self.send_with(WsMsg::TEXT, |buf| {
serde_json_core::to_slice(msg, buf).map_err(|e| e.into())
})
.await
} }
} }
pub struct Ws<'a, const BUF_SIZE: usize = 1024> { pub struct Ws<'a, const BUF_SIZE: usize = 1024, const RES_HEAD_BUF_SIZE: usize = 256> {
rx: WsRx<'a, BUF_SIZE>, rx: WsRx<'a, BUF_SIZE>,
tx: WsTx<'a>, tx: WsTx<'a, RES_HEAD_BUF_SIZE>,
pub last_msg: Instant,
name: &'a str, name: &'a str,
} }
impl<'a, const BUF_SIZE: usize> Ws<'a, BUF_SIZE> { impl<'a, const BUF_SIZE: usize, const HEAD_BUF_SIZE: usize> Ws<'a, BUF_SIZE, HEAD_BUF_SIZE> {
pub fn new(socket: &'a mut TcpSocket, buf: &'a mut [u8; BUF_SIZE], name: &'a str) -> Self { pub fn new(
socket: &'a mut TcpSocket,
buf: &'a mut [u8; BUF_SIZE],
head_buf: &'a mut Vec<u8, HEAD_BUF_SIZE>,
name: &'a str,
) -> Self {
let (rx, tx) = socket.split(); let (rx, tx) = socket.split();
Self { Self {
rx: WsRx { rx: WsRx {
socket: rx, socket: rx,
buf, buf,
msg_in_buf: None, last_msg: Instant::MIN,
},
tx: WsTx {
socket: tx,
head_buf,
}, },
tx: WsTx { socket: tx },
last_msg: Instant::MIN,
name, name,
} }
} }
/// Do this often to respond to pings // Do this often to respond to pings
pub async fn rcv(&mut self) -> Result<Option<WsMsg>> { async fn rcv(&mut self) -> Result<Option<WsMsg>, ()> {
let n = match self.rx.msg_in_buf.take() { if !self.rx.socket.read_ready().unwrap() {
Some(n) => { return Ok(None);
defmt::assert!(n.0 + n.1 <= self.rx.buf.len()); }
self.rx.buf.copy_within(n.0..n.0 + n.1, 0); let n = match self.rx.socket.read(self.rx.buf).await {
if unwrap!(self.rx.socket.read_ready()) { Ok(0) => {
let n_rcv = self warn!("read EOF");
.rx return Err(());
.socket
.read(&mut self.rx.buf[n.1..])
.await
.map_err(|_| anyhow!("connection reset"))?;
if n_rcv == 0 {
return Err(anyhow!("read EOF"));
}
n.1 + n_rcv
} else {
n.1
}
} }
None => { Ok(n) => n,
if unwrap!(self.rx.socket.read_ready()) { Err(e) => {
match self warn!("Socket {}: read error: {:?}", self.name, e);
.rx return Err(());
.socket
.read(self.rx.buf)
.await
.map_err(|_| anyhow!("connection reset"))?
{
0 => {
return Err(anyhow!("read EOF"));
}
n => n,
}
} else {
return Ok(None);
}
} }
}; };
if self.rx.buf[0] & 0b1000_0000 == 0 { if self.rx.buf[0] & 0b1000_0000 == 0 {
return Err(anyhow!("fragmented ws message")); warn!("Fragmented ws messages are not supported!");
return Err(());
} }
if self.rx.buf[0] & 0b0111_0000 != 0 { if self.rx.buf[0] & 0b0111_0000 != 0 {
return Err(anyhow!( warn!(
"reserved ws bits are set {}", "Reserved ws bits are set : {}",
(self.rx.buf[0] >> 4) & 0b0111 (self.rx.buf[0] >> 4) & 0b0111
)); );
return Err(());
} }
let (length, n_after_length) = match self.rx.buf[1] & 0b0111_1111 { let (length, n_after_length) = match self.rx.buf[1] & 0b0111_1111 {
126 => ( 126 => (
u64::from_le_bytes([0, 0, 0, 0, 0, 0, self.rx.buf[2], self.rx.buf[3]]), u64::from_le_bytes([0, 0, 0, 0, 0, 0, self.rx.buf[2], self.rx.buf[3]]),
4, 4,
), ),
127 => (u64::from_le_bytes(self.rx.buf[2..10].try_into()?), 10), 127 => (
u64::from_le_bytes(self.rx.buf[2..10].try_into().unwrap()),
10,
),
l => (l as u64, 2), l => (l as u64, 2),
}; };
if length > 512 { if length > 512 {
return Err(anyhow!("ws payload bigger than 512!")); warn!("ws payload bigger than 512!");
return Err(());
} }
let content = if self.rx.buf[1] & 0b1000_0000 != 0 { let content = if self.rx.buf[1] & 0b1000_0000 != 0 {
// masked message // masked message
if n_after_length + 4 + length as usize > n { if n_after_length + 4 + length as usize > n {
return Err(anyhow!("ws payload smaller than length")); warn!("ws payload smaller than length");
return Err(());
} }
let mask_key: [u8; 4] = self.rx.buf[n_after_length..n_after_length + 4].try_into()?; let mask_key: [u8; 4] = self.rx.buf[n_after_length..n_after_length + 4]
.try_into()
.unwrap();
for (i, x) in self.rx.buf[n_after_length + 4..n_after_length + 4 + length as usize] for (i, x) in self.rx.buf[n_after_length + 4..n_after_length + 4 + length as usize]
.iter_mut() .iter_mut()
.enumerate() .enumerate()
{ {
*x ^= mask_key[i % 4]; *x ^= mask_key[i & 0xff];
}
if n_after_length + 4 + (length as usize) < n {
self.rx.msg_in_buf = Some((
n_after_length + 4 + (length as usize),
(n - (n_after_length + 4 + (length as usize))),
));
} }
&self.rx.buf[n_after_length + 4..n_after_length + 4 + length as usize] &self.rx.buf[n_after_length + 4..n_after_length + 4 + length as usize]
} else { } else {
if n_after_length + length as usize > n { if n_after_length + length as usize > n {
return Err(anyhow!("ws payload smaller than length")); warn!("ws payload smaller than length");
} return Err(());
if n_after_length + (length as usize) < n {
self.rx.msg_in_buf = Some((
n_after_length + (length as usize),
(n - (n_after_length + (length as usize))),
));
} }
&self.rx.buf[n_after_length..n_after_length + length as usize] &self.rx.buf[n_after_length..n_after_length + length as usize]
}; };
self.last_msg = Instant::now(); self.rx.last_msg = Instant::now();
match self.rx.buf[0] & 0b0000_1111 { match self.rx.buf[0] & 0b0000_1111 {
// Text message // Text message
1 => { 1 => {
let content = from_utf8(&content)?; let content = from_utf8(&content).map_err(|_| ())?;
info!("Received text : {:?}", content);
Ok(Some(WsMsg::Text(content))) Ok(Some(WsMsg::Text(content)))
} }
// Bytes
2 => Ok(Some(WsMsg::Bytes(content))),
// Ping // Ping
9 => { 9 => {
self.tx.send(WsMsg::Pong(&content)).await?; self.tx.send(WsMsg::Pong(&content)).await?;
@ -242,37 +176,12 @@ impl<'a, const BUF_SIZE: usize> Ws<'a, BUF_SIZE> {
// Pong // Pong
10 => Ok(Some(WsMsg::Pong(&content))), 10 => Ok(Some(WsMsg::Pong(&content))),
c => { c => {
warn!("Unknown ws op code (ignoring) : {}", c); info!("Unknown ws op code (ignoring) : {}", c);
Ok(Some(WsMsg::Unknown(c, &content))) Ok(Some(WsMsg::Unknown(c, &content)))
} }
} }
} }
pub async fn send(&mut self, msg: WsMsg<'_>) -> Result<()> { pub async fn send(&mut self, msg: WsMsg<'a>) -> Result<(), ()> {
self.tx.send(msg).await?; self.tx.send(msg).await
self.last_msg = Instant::now();
Ok(())
}
pub async fn send_json<T: serde::Serialize>(&mut self, msg: &T) -> Result<()> {
self.tx.send_json(msg).await?;
self.last_msg = Instant::now();
Ok(())
}
pub async fn send_with<F: Fn(&mut [u8]) -> Result<usize>>(
&mut self,
msg_code: u8,
f: F,
) -> Result<()> {
self.tx.send_with(msg_code, f).await?;
self.last_msg = Instant::now();
Ok(())
}
pub async fn send_with_no_flush<F: FnOnce(&mut [u8]) -> Result<usize>>(
&mut self,
msg_code: u8,
f: F,
) -> Result<()> {
self.tx.send_with_no_flush(msg_code, f).await?;
self.last_msg = Instant::now();
Ok(())
} }
} }

View File

@ -1 +0,0 @@
<!doctype html><html><body><h1>Apps</h1><ul><li><a href="/ttt?team=0">Tic Tac Toe</a>(team blue)</li><li><a href="/ttt?team=1">Tic Tac Toe</a>(team red)</li></ul></body></html>

View File

@ -1 +0,0 @@
<!doctype html><head><style type="text/css"> body { #grid { .cell { border: 1px dotted black; padding: 33%; } .cell[team="0"] { background-color: dodgerblue; } .cell[team="1"] { background-color: firebrick; } display: grid; border: 1px solid black; grid-template-rows: 1fr 1fr 1fr; grid-template-columns: 1fr 1fr 1fr; } } </style><script src="/ttt.js" defer></script></head><html><body><h1>TicTacToe</h1><h3 id="team"></h3><h3 id="winner"></h3><div id="grid"></div></body></html>

1
static/ttt.min.js vendored
View File

@ -1 +0,0 @@
if(0!=team&&1!=team)throw"team is not 0 or 1! team="+team;const teams=[{name:"blue",color:"dodgerblue",port:"8080"},{name:"red",color:"firebrick",port:"8081"}];document.getElementById("team").innerHTML='Team : <span style="color:'+teams[team].color+'">'+teams[team].name+"</span>";const ws=new WebSocket("ws://192.254.0.2:"+teams[team].port+"/"+teams[team].name);ws.onmessage=e=>{if("string"==typeof e.data){let t=JSON.parse(e.data),n=[];for(let e=0;e<9;e++){let a,r=t.board[e];a=t.turn==team&&null===r?"button":"div";let m=document.createElement(a);m.classList.add("cell"),"button"===a&&m.addEventListener("click",(t=>{ws.send(new Uint8Array([e]))})),m.setAttribute("team",r),n.push(m)}document.getElementById("grid").replaceChildren(...n),null==t.turn?null==t.winner?document.getElementById("winner").innerHTML="Draw!":document.getElementById("winner").innerHTML='Winner : <span style="color:'+teams[t.winner].color+'">'+teams[t.winner].name+"</span>":document.getElementById("winner").innerHTML=""}};