urdf_viz/
web_server.rs

1use std::{future::Future, sync::Arc};
2
3use axum::{
4    extract::State,
5    http::StatusCode,
6    routing::{get, post},
7    Json, Router,
8};
9use serde::{Deserialize, Serialize};
10
11use crate::handle::{JointNamesAndPositions, RobotOrigin, RobotStateHandle};
12
13type Handle = Arc<RobotStateHandle>;
14
15#[derive(Deserialize, Serialize, Debug, Clone)]
16struct ResultResponse {
17    is_ok: bool,
18    reason: String,
19}
20
21impl ResultResponse {
22    const SUCCESS: Self = ResultResponse {
23        is_ok: true,
24        reason: String::new(),
25    };
26}
27
28#[derive(Debug)]
29pub struct WebServer {
30    port: u16,
31    handle: Arc<RobotStateHandle>,
32}
33
34impl WebServer {
35    pub fn new(port: u16, handle: Arc<RobotStateHandle>) -> Self {
36        Self { port, handle }
37    }
38
39    pub fn handle(&self) -> Arc<RobotStateHandle> {
40        self.handle.clone()
41    }
42
43    pub fn bind(self) -> crate::Result<impl Future<Output = crate::Result<()>> + Send> {
44        let app = app(self.handle());
45
46        // Use std::net::TcpListener::bind to early catch web server startup failure
47        let addr: std::net::SocketAddr = ([0, 0, 0, 0], self.port).into();
48        let listener = (|| {
49            let l = std::net::TcpListener::bind(addr)?;
50            l.set_nonblocking(true)?;
51            tokio::net::TcpListener::from_std(l)
52        })()
53        .map_err(|e| format!("error binding to {addr}: {e}"))?;
54
55        let server = axum::serve(listener, app.into_make_service());
56        Ok(async move { server.await.map_err(|e| crate::Error::Other(e.to_string())) })
57    }
58}
59
60fn app(handle: Handle) -> Router {
61    Router::new()
62        .route("/set_joint_positions", post(set_joint_positions))
63        .route("/set_robot_origin", post(set_robot_origin))
64        .route("/set_reload_request", post(set_reload_request))
65        .route("/get_joint_positions", get(get_joint_positions))
66        .route("/get_robot_origin", get(get_robot_origin))
67        .route("/get_urdf_text", get(get_urdf_text))
68        .with_state(handle)
69        .layer(tower_http::trace::TraceLayer::new_for_http())
70}
71
72async fn set_reload_request(State(handle): State<Handle>) -> Json<ResultResponse> {
73    handle.set_reload_request();
74    Json(ResultResponse::SUCCESS)
75}
76
77async fn set_joint_positions(
78    State(handle): State<Handle>,
79    Json(jp): Json<JointNamesAndPositions>,
80) -> Json<ResultResponse> {
81    if jp.names.len() != jp.positions.len() {
82        Json(ResultResponse {
83            is_ok: false,
84            reason: format!(
85                "names and positions size mismatch ({} != {})",
86                jp.names.len(),
87                jp.positions.len()
88            ),
89        })
90    } else {
91        handle.set_target_joint_positions(jp);
92        Json(ResultResponse::SUCCESS)
93    }
94}
95
96async fn set_robot_origin(
97    State(handle): State<Handle>,
98    Json(robot_origin): Json<RobotOrigin>,
99) -> Json<ResultResponse> {
100    handle.set_target_robot_origin(robot_origin);
101    Json(ResultResponse::SUCCESS)
102}
103
104async fn get_joint_positions(State(handle): State<Handle>) -> Json<JointNamesAndPositions> {
105    Json(handle.current_joint_positions().clone())
106}
107
108async fn get_robot_origin(State(handle): State<Handle>) -> Json<RobotOrigin> {
109    Json(handle.current_robot_origin().clone())
110}
111
112async fn get_urdf_text(State(handle): State<Handle>) -> Result<String, StatusCode> {
113    match handle.urdf_text() {
114        Some(text) => Ok(text.clone()),
115        None => Err(StatusCode::NOT_FOUND),
116    }
117}