From 41752e9408e8dfe9c20cf4e6b6be9b8a92d8e3fd Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 18:53:35 +0100 Subject: [PATCH 01/13] add debugging for x5_camera --- Cargo.lock | 1 + booster_sdk/src/dds/rpc.rs | 88 +++++++++++++++++++++++++++++++++-- booster_sdk/src/dds/topics.rs | 4 +- booster_sdk_py/Cargo.toml | 1 + booster_sdk_py/src/lib.rs | 38 +++++++++++++++ 5 files changed, 127 insertions(+), 5 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index b9c33a4..abd9708 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -67,6 +67,7 @@ dependencies = [ "pyo3", "tokio", "tracing", + "tracing-subscriber", ] [[package]] diff --git a/booster_sdk/src/dds/rpc.rs b/booster_sdk/src/dds/rpc.rs index f90a4da..1a5ccd6 100644 --- a/booster_sdk/src/dds/rpc.rs +++ b/booster_sdk/src/dds/rpc.rs @@ -54,6 +54,7 @@ pub struct RpcClient { request_writer: rustdds::no_key::DataWriter, response_reader: Arc>>, default_timeout: Duration, + service_topic: String, } #[derive(Debug, Deserialize, Default)] @@ -99,6 +100,33 @@ fn normalize_service_topic(service_topic: &str) -> String { trimmed.to_owned() } +fn rpc_debug_enabled() -> bool { + std::env::var("BOOSTER_RPC_DEBUG") + .map(|value| { + let value = value.trim(); + value == "1" + || value.eq_ignore_ascii_case("true") + || value.eq_ignore_ascii_case("yes") + || value.eq_ignore_ascii_case("on") + }) + .unwrap_or(false) +} + +fn preview_for_log(value: &str, max_chars: usize) -> String { + let mut preview = String::new(); + let mut chars = value.chars(); + for _ in 0..max_chars { + match chars.next() { + Some(ch) => preview.push(ch), + None => return preview.replace('\n', "\\n"), + } + } + if chars.next().is_some() { + preview.push_str("..."); + } + preview.replace('\n', "\\n") +} + impl RpcClient { pub fn for_topic(options: RpcClientOptions, service_topic: impl Into) -> Result { Self::new(options.with_service_topic(service_topic)) @@ -120,6 +148,7 @@ impl RpcClient { request_writer: request_writer.into_inner(), response_reader: Arc::new(Mutex::new(response_reader)), default_timeout: options.default_timeout, + service_topic, }) } @@ -199,9 +228,23 @@ impl RpcClient { where R: DeserializeOwned + Send + 'static, { + let debug_enabled = rpc_debug_enabled(); let request_id = Uuid::new_v4().to_string(); let body = body.into(); let header = serde_json::json!({ "api_id": api_id }).to_string(); + let service_topic = self.service_topic.clone(); + + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + header = %preview_for_log(&header, 200), + body = %preview_for_log(&body, 300), + "send rpc request" + ); + } let request = RpcReqMsg { uuid: request_id.clone(), @@ -224,19 +267,48 @@ impl RpcClient { .map_err(|err| DdsError::ReceiveFailed(err.to_string()))?; loop { if Instant::now() >= deadline { + if debug_enabled { + tracing::warn!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + timeout_ms = timeout.as_millis(), + "rpc timeout" + ); + } return Err(RpcError::Timeout { timeout }.into()); } match reader.take_next_sample() { Ok(Some(sample)) => { let response = sample.into_value(); - if response.uuid != request_id { - continue; - } let status_code = parse_status_from_header(&response.header).unwrap_or(0); + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + response_uuid = %response.uuid, + status_code, + header = %preview_for_log(&response.header, 200), + body = %preview_for_log(&response.body, 300), + "recv rpc response" + ); + } if status_code == -1 { + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + "ignoring intermediate status=-1" + ); + } continue; } @@ -260,6 +332,16 @@ impl RpcClient { } Ok(None) => std::thread::sleep(Duration::from_millis(5)), Err(err) => { + if debug_enabled { + tracing::warn!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + error = %err, + "rpc receive error" + ); + } return Err(DdsError::ReceiveFailed(err.to_string()).into()); } } diff --git a/booster_sdk/src/dds/topics.rs b/booster_sdk/src/dds/topics.rs index 8c9785b..b0aa2ff 100644 --- a/booster_sdk/src/dds/topics.rs +++ b/booster_sdk/src/dds/topics.rs @@ -53,7 +53,7 @@ pub fn rpc_request_topic(service_topic: &str) -> TopicSpec { TopicSpec { name: format!("{service_topic}Req"), type_name: TYPE_RPC_REQ, - qos: qos_reliable_keep_last(10), + qos: qos_best_effort_keep_last(10), kind: TopicKind::NoKey, } } @@ -62,7 +62,7 @@ pub fn rpc_response_topic(service_topic: &str) -> TopicSpec { TopicSpec { name: format!("{service_topic}Resp"), type_name: TYPE_RPC_RESP, - qos: qos_reliable_keep_last(10), + qos: qos_best_effort_keep_last(10), kind: TopicKind::NoKey, } } diff --git a/booster_sdk_py/Cargo.toml b/booster_sdk_py/Cargo.toml index ce8e6c8..21e5b82 100644 --- a/booster_sdk_py/Cargo.toml +++ b/booster_sdk_py/Cargo.toml @@ -16,3 +16,4 @@ booster_sdk = { workspace = true } pyo3 = { workspace = true } tokio = { workspace = true } tracing = { workspace = true } +tracing-subscriber = { workspace = true } diff --git a/booster_sdk_py/src/lib.rs b/booster_sdk_py/src/lib.rs index 9c9218f..48d8f8b 100644 --- a/booster_sdk_py/src/lib.rs +++ b/booster_sdk_py/src/lib.rs @@ -1,8 +1,11 @@ mod client; mod runtime; +use std::sync::OnceLock; + use booster_sdk::{client::ai::BOOSTER_ROBOT_USER_ID, types::BoosterError}; use pyo3::{exceptions::PyException, prelude::*, types::PyModule}; +use tracing_subscriber::{EnvFilter, fmt}; pyo3::create_exception!(booster_sdk_bindings, BoosterSdkError, PyException); @@ -10,8 +13,43 @@ pub(crate) fn to_py_err(err: BoosterError) -> PyErr { BoosterSdkError::new_err(err.to_string()) } +fn rpc_debug_enabled() -> bool { + std::env::var("BOOSTER_RPC_DEBUG") + .map(|value| { + let value = value.trim(); + value == "1" + || value.eq_ignore_ascii_case("true") + || value.eq_ignore_ascii_case("yes") + || value.eq_ignore_ascii_case("on") + }) + .unwrap_or(false) +} + +fn init_tracing_for_python() { + static INIT: OnceLock<()> = OnceLock::new(); + INIT.get_or_init(|| { + if !rpc_debug_enabled() { + return; + } + + let env_filter = std::env::var("RUST_LOG") + .ok() + .and_then(|value| EnvFilter::try_new(value).ok()) + .unwrap_or_else(|| EnvFilter::new("booster_sdk::rpc=debug")); + + let _ = fmt() + .with_env_filter(env_filter) + .with_target(true) + .with_thread_ids(true) + .with_writer(std::io::stderr) + .try_init(); + }); +} + #[pymodule] fn booster_sdk_bindings(py: Python<'_>, m: &Bound<'_, PyModule>) -> PyResult<()> { + init_tracing_for_python(); + m.add("BoosterSdkError", py.get_type::())?; m.add("BOOSTER_ROBOT_USER_ID", BOOSTER_ROBOT_USER_ID)?; From 9ede47082056613f79bc5c4113b98ca5b85477fc Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 18:54:28 +0100 Subject: [PATCH 02/13] 0.1.0-alpha.9 --- Cargo.lock | 4 ++-- Cargo.toml | 2 +- pixi.toml | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index abd9708..d711e5f 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -46,7 +46,7 @@ checksum = "812e12b5285cc515a9c72a5c1d3b6d46a19dac5acfef5265968c166106e31dd3" [[package]] name = "booster_sdk" -version = "0.1.0-alpha.8" +version = "0.1.0-alpha.9" dependencies = [ "rustdds", "serde", @@ -61,7 +61,7 @@ dependencies = [ [[package]] name = "booster_sdk_py" -version = "0.1.0-alpha.8" +version = "0.1.0-alpha.9" dependencies = [ "booster_sdk", "pyo3", diff --git a/Cargo.toml b/Cargo.toml index 717cbdd..f595515 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -3,7 +3,7 @@ members = ["booster_sdk", "booster_sdk_py"] resolver = "2" [workspace.package] -version = "0.1.0-alpha.8" +version = "0.1.0-alpha.9" edition = "2024" authors = ["Team whIRLwind"] license = "MIT OR Apache-2.0" diff --git a/pixi.toml b/pixi.toml index 81aa884..ee40ce5 100644 --- a/pixi.toml +++ b/pixi.toml @@ -3,7 +3,7 @@ authors = ["Team whIRLwind"] channels = ["conda-forge"] name = "booster-sdk" platforms = ["osx-arm64", "linux-64", "linux-aarch64"] -version = "0.1.0-alpha.8" +version = "0.1.0-alpha.9" [environments] py = ["wheel-build", "python-tasks"] From 40b0426c87e13a5cb70f460619ece777954d5909 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 20:48:11 +0100 Subject: [PATCH 03/13] add example --- booster_sdk/examples/x5_camera_rpc_check.rs | 59 +++++++++++++++++++++ 1 file changed, 59 insertions(+) create mode 100644 booster_sdk/examples/x5_camera_rpc_check.rs diff --git a/booster_sdk/examples/x5_camera_rpc_check.rs b/booster_sdk/examples/x5_camera_rpc_check.rs new file mode 100644 index 0000000..5df4016 --- /dev/null +++ b/booster_sdk/examples/x5_camera_rpc_check.rs @@ -0,0 +1,59 @@ +//! Quick X5 camera RPC connectivity check. +//! +//! Run with: +//! `cargo run -p booster_sdk --example x5_camera_rpc_check` +//! +//! Optional env vars: +//! - `BOOSTER_DOMAIN_ID` (default: `0`) +//! - `BOOSTER_TIMEOUT_MS` (default: `3000`) +//! - `BOOSTER_RPC_DEBUG` (`1`/`true` for verbose RPC logs) + +use std::time::{Duration, Instant}; + +use booster_sdk::client::x5_camera::X5CameraClient; +use booster_sdk::dds::{RpcClientOptions, X5_CAMERA_CONTROL_API_TOPIC}; + +#[tokio::main] +async fn main() -> Result<(), Box> { + tracing_subscriber::fmt().with_env_filter("info").init(); + + let domain_id = std::env::var("BOOSTER_DOMAIN_ID") + .ok() + .and_then(|v| v.parse::().ok()) + .unwrap_or(0); + let timeout_ms = std::env::var("BOOSTER_TIMEOUT_MS") + .ok() + .and_then(|v| v.parse::().ok()) + .unwrap_or(3000); + + println!( + "X5 RPC check: domain_id={}, timeout_ms={}, topic={}", + domain_id, timeout_ms, X5_CAMERA_CONTROL_API_TOPIC + ); + + let client = X5CameraClient::with_options(RpcClientOptions { + domain_id, + default_timeout: Duration::from_millis(timeout_ms), + service_topic: X5_CAMERA_CONTROL_API_TOPIC.to_owned(), + })?; + + let started = Instant::now(); + match client.get_status().await { + Ok(resp) => { + let elapsed = started.elapsed(); + println!( + "OK: status={} status_enum={:?} elapsed_ms={}", + resp.status, + resp.status_enum(), + elapsed.as_millis() + ); + Ok(()) + } + Err(err) => { + let elapsed = started.elapsed(); + eprintln!("ERR: {err}"); + eprintln!("elapsed_ms={}", elapsed.as_millis()); + std::process::exit(2); + } + } +} From 46b6edf28c02d0434abee9109fab379196278ee9 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 20:57:29 +0100 Subject: [PATCH 04/13] fix topic check --- booster_sdk/examples/x5_camera_rpc_check.rs | 7 ++++++- booster_sdk/src/dds/rpc.rs | 14 ++++++++++++++ booster_sdk/src/dds/topics.rs | 2 +- 3 files changed, 21 insertions(+), 2 deletions(-) diff --git a/booster_sdk/examples/x5_camera_rpc_check.rs b/booster_sdk/examples/x5_camera_rpc_check.rs index 5df4016..4aca1bd 100644 --- a/booster_sdk/examples/x5_camera_rpc_check.rs +++ b/booster_sdk/examples/x5_camera_rpc_check.rs @@ -15,7 +15,9 @@ use booster_sdk::dds::{RpcClientOptions, X5_CAMERA_CONTROL_API_TOPIC}; #[tokio::main] async fn main() -> Result<(), Box> { - tracing_subscriber::fmt().with_env_filter("info").init(); + let env_filter = tracing_subscriber::EnvFilter::try_from_default_env() + .unwrap_or_else(|_| tracing_subscriber::EnvFilter::new("error")); + tracing_subscriber::fmt().with_env_filter(env_filter).init(); let domain_id = std::env::var("BOOSTER_DOMAIN_ID") .ok() @@ -37,6 +39,9 @@ async fn main() -> Result<(), Box> { service_topic: X5_CAMERA_CONTROL_API_TOPIC.to_owned(), })?; + // Give DDS discovery a moment to settle before the first RPC call. + tokio::time::sleep(Duration::from_millis(500)).await; + let started = Instant::now(); match client.get_status().await { Ok(resp) => { diff --git a/booster_sdk/src/dds/rpc.rs b/booster_sdk/src/dds/rpc.rs index 1a5ccd6..af881cd 100644 --- a/booster_sdk/src/dds/rpc.rs +++ b/booster_sdk/src/dds/rpc.rs @@ -284,6 +284,20 @@ impl RpcClient { Ok(Some(sample)) => { let response = sample.into_value(); + if response.uuid != request_id { + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %service_topic, + api_id, + request_uuid = %request_id, + response_uuid = %response.uuid, + "ignoring response for a different request uuid" + ); + } + continue; + } + let status_code = parse_status_from_header(&response.header).unwrap_or(0); if debug_enabled { tracing::debug!( diff --git a/booster_sdk/src/dds/topics.rs b/booster_sdk/src/dds/topics.rs index b0aa2ff..91ce651 100644 --- a/booster_sdk/src/dds/topics.rs +++ b/booster_sdk/src/dds/topics.rs @@ -62,7 +62,7 @@ pub fn rpc_response_topic(service_topic: &str) -> TopicSpec { TopicSpec { name: format!("{service_topic}Resp"), type_name: TYPE_RPC_RESP, - qos: qos_best_effort_keep_last(10), + qos: qos_reliable_keep_last(10), kind: TopicKind::NoKey, } } From 088e296dbe9c35035be9d674c164a2321f43ef3d Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 21:02:54 +0100 Subject: [PATCH 05/13] more testing --- booster_sdk/src/dds/qos.rs | 12 +++++++++++- booster_sdk/src/dds/topics.rs | 9 ++++++--- 2 files changed, 17 insertions(+), 4 deletions(-) diff --git a/booster_sdk/src/dds/qos.rs b/booster_sdk/src/dds/qos.rs index d0f9632..00e3b2e 100644 --- a/booster_sdk/src/dds/qos.rs +++ b/booster_sdk/src/dds/qos.rs @@ -2,7 +2,7 @@ use rustdds::{ Duration, QosPolicies, QosPolicyBuilder, - policy::{History, Reliability}, + policy::{Durability, History, Reliability}, }; pub fn qos_best_effort_keep_last(depth: i32) -> QosPolicies { @@ -21,6 +21,16 @@ pub fn qos_reliable_keep_last(depth: i32) -> QosPolicies { .build() } +pub fn qos_reliable_transient_local_keep_last(depth: i32) -> QosPolicies { + QosPolicyBuilder::new() + .durability(Durability::TransientLocal) + .reliability(Reliability::Reliable { + max_blocking_time: Duration::from_millis(100), + }) + .history(History::KeepLast { depth }) + .build() +} + pub fn qos_reliable_keep_all() -> QosPolicies { QosPolicyBuilder::new() .reliability(Reliability::Reliable { diff --git a/booster_sdk/src/dds/topics.rs b/booster_sdk/src/dds/topics.rs index 91ce651..21dd732 100644 --- a/booster_sdk/src/dds/topics.rs +++ b/booster_sdk/src/dds/topics.rs @@ -4,7 +4,10 @@ use rustdds::{QosPolicies, Topic, TopicKind}; use crate::types::{DdsError, Result}; -use super::qos::{qos_best_effort_keep_last, qos_reliable_keep_all, qos_reliable_keep_last}; +use super::qos::{ + qos_best_effort_keep_last, qos_reliable_keep_all, qos_reliable_keep_last, + qos_reliable_transient_local_keep_last, +}; #[derive(Debug, Clone)] pub struct TopicSpec { @@ -53,7 +56,7 @@ pub fn rpc_request_topic(service_topic: &str) -> TopicSpec { TopicSpec { name: format!("{service_topic}Req"), type_name: TYPE_RPC_REQ, - qos: qos_best_effort_keep_last(10), + qos: qos_reliable_keep_last(10), kind: TopicKind::NoKey, } } @@ -62,7 +65,7 @@ pub fn rpc_response_topic(service_topic: &str) -> TopicSpec { TopicSpec { name: format!("{service_topic}Resp"), type_name: TYPE_RPC_RESP, - qos: qos_reliable_keep_last(10), + qos: qos_reliable_transient_local_keep_last(10), kind: TopicKind::NoKey, } } From 67066d8eb0d2bd8a2e7fe44d84e80fbe2e86ee85 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 21:07:34 +0100 Subject: [PATCH 06/13] try --- booster_sdk/src/dds/rpc.rs | 40 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/booster_sdk/src/dds/rpc.rs b/booster_sdk/src/dds/rpc.rs index af881cd..41776d0 100644 --- a/booster_sdk/src/dds/rpc.rs +++ b/booster_sdk/src/dds/rpc.rs @@ -112,6 +112,15 @@ fn rpc_debug_enabled() -> bool { .unwrap_or(false) } +fn rpc_match_timeout() -> Duration { + let default_ms = 8000_u64; + let ms = std::env::var("BOOSTER_RPC_MATCH_TIMEOUT_MS") + .ok() + .and_then(|value| value.parse::().ok()) + .unwrap_or(default_ms); + Duration::from_millis(ms) +} + fn preview_for_log(value: &str, max_chars: usize) -> String { let mut preview = String::new(); let mut chars = value.chars(); @@ -128,6 +137,19 @@ fn preview_for_log(value: &str, max_chars: usize) -> String { } impl RpcClient { + fn wait_for_request_match(&self, max_wait: Duration) -> bool { + let deadline = Instant::now() + max_wait; + loop { + if !self.request_writer.get_matched_subscriptions().is_empty() { + return true; + } + if Instant::now() >= deadline { + return false; + } + std::thread::sleep(Duration::from_millis(50)); + } + } + pub fn for_topic(options: RpcClientOptions, service_topic: impl Into) -> Result { Self::new(options.with_service_topic(service_topic)) } @@ -229,6 +251,24 @@ impl RpcClient { R: DeserializeOwned + Send + 'static, { let debug_enabled = rpc_debug_enabled(); + let match_timeout = rpc_match_timeout(); + let matched = self.wait_for_request_match(match_timeout); + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %self.service_topic, + matched, + match_wait_ms = match_timeout.as_millis(), + "rpc request writer match status" + ); + } + if !matched { + return Err(RpcError::Timeout { + timeout: match_timeout, + } + .into()); + } + let request_id = Uuid::new_v4().to_string(); let body = body.into(); let header = serde_json::json!({ "api_id": api_id }).to_string(); From 26d21a7d6255f6b35c65588cdaab529cbf4908ca Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 21:19:38 +0100 Subject: [PATCH 07/13] waiting --- booster_sdk/examples/x5_camera_rpc_check.rs | 68 ++++++++++++++------- booster_sdk/src/dds/rpc.rs | 40 ------------ 2 files changed, 47 insertions(+), 61 deletions(-) diff --git a/booster_sdk/examples/x5_camera_rpc_check.rs b/booster_sdk/examples/x5_camera_rpc_check.rs index 4aca1bd..356b283 100644 --- a/booster_sdk/examples/x5_camera_rpc_check.rs +++ b/booster_sdk/examples/x5_camera_rpc_check.rs @@ -6,6 +6,8 @@ //! Optional env vars: //! - `BOOSTER_DOMAIN_ID` (default: `0`) //! - `BOOSTER_TIMEOUT_MS` (default: `3000`) +//! - `BOOSTER_STARTUP_WAIT_MS` (default: `7000`) +//! - `BOOSTER_RETRIES` (default: `3`) //! - `BOOSTER_RPC_DEBUG` (`1`/`true` for verbose RPC logs) use std::time::{Duration, Instant}; @@ -27,10 +29,18 @@ async fn main() -> Result<(), Box> { .ok() .and_then(|v| v.parse::().ok()) .unwrap_or(3000); + let startup_wait_ms = std::env::var("BOOSTER_STARTUP_WAIT_MS") + .ok() + .and_then(|v| v.parse::().ok()) + .unwrap_or(7000); + let retries = std::env::var("BOOSTER_RETRIES") + .ok() + .and_then(|v| v.parse::().ok()) + .unwrap_or(3); println!( - "X5 RPC check: domain_id={}, timeout_ms={}, topic={}", - domain_id, timeout_ms, X5_CAMERA_CONTROL_API_TOPIC + "X5 RPC check: domain_id={}, timeout_ms={}, startup_wait_ms={}, retries={}, topic={}", + domain_id, timeout_ms, startup_wait_ms, retries, X5_CAMERA_CONTROL_API_TOPIC ); let client = X5CameraClient::with_options(RpcClientOptions { @@ -39,26 +49,42 @@ async fn main() -> Result<(), Box> { service_topic: X5_CAMERA_CONTROL_API_TOPIC.to_owned(), })?; - // Give DDS discovery a moment to settle before the first RPC call. - tokio::time::sleep(Duration::from_millis(500)).await; + // Mimic "waiting for service to become available" before first call. + tokio::time::sleep(Duration::from_millis(startup_wait_ms)).await; - let started = Instant::now(); - match client.get_status().await { - Ok(resp) => { - let elapsed = started.elapsed(); - println!( - "OK: status={} status_enum={:?} elapsed_ms={}", - resp.status, - resp.status_enum(), - elapsed.as_millis() - ); - Ok(()) - } - Err(err) => { - let elapsed = started.elapsed(); - eprintln!("ERR: {err}"); - eprintln!("elapsed_ms={}", elapsed.as_millis()); - std::process::exit(2); + let total_started = Instant::now(); + let mut last_err = None; + for attempt in 1..=retries { + let started = Instant::now(); + match client.get_status().await { + Ok(resp) => { + let elapsed = started.elapsed(); + let total_elapsed = total_started.elapsed(); + println!( + "OK: attempt={} status={} status_enum={:?} elapsed_ms={} total_elapsed_ms={}", + attempt, + resp.status, + resp.status_enum(), + elapsed.as_millis(), + total_elapsed.as_millis() + ); + return Ok(()); + } + Err(err) => { + let elapsed = started.elapsed(); + eprintln!("attempt {} failed: {} (elapsed_ms={})", attempt, err, elapsed.as_millis()); + last_err = Some(err.to_string()); + if attempt < retries { + tokio::time::sleep(Duration::from_millis(1000)).await; + } + } } } + + eprintln!( + "ERR: {}", + last_err.unwrap_or_else(|| "unknown error".to_string()) + ); + eprintln!("total_elapsed_ms={}", total_started.elapsed().as_millis()); + std::process::exit(2); } diff --git a/booster_sdk/src/dds/rpc.rs b/booster_sdk/src/dds/rpc.rs index 41776d0..af881cd 100644 --- a/booster_sdk/src/dds/rpc.rs +++ b/booster_sdk/src/dds/rpc.rs @@ -112,15 +112,6 @@ fn rpc_debug_enabled() -> bool { .unwrap_or(false) } -fn rpc_match_timeout() -> Duration { - let default_ms = 8000_u64; - let ms = std::env::var("BOOSTER_RPC_MATCH_TIMEOUT_MS") - .ok() - .and_then(|value| value.parse::().ok()) - .unwrap_or(default_ms); - Duration::from_millis(ms) -} - fn preview_for_log(value: &str, max_chars: usize) -> String { let mut preview = String::new(); let mut chars = value.chars(); @@ -137,19 +128,6 @@ fn preview_for_log(value: &str, max_chars: usize) -> String { } impl RpcClient { - fn wait_for_request_match(&self, max_wait: Duration) -> bool { - let deadline = Instant::now() + max_wait; - loop { - if !self.request_writer.get_matched_subscriptions().is_empty() { - return true; - } - if Instant::now() >= deadline { - return false; - } - std::thread::sleep(Duration::from_millis(50)); - } - } - pub fn for_topic(options: RpcClientOptions, service_topic: impl Into) -> Result { Self::new(options.with_service_topic(service_topic)) } @@ -251,24 +229,6 @@ impl RpcClient { R: DeserializeOwned + Send + 'static, { let debug_enabled = rpc_debug_enabled(); - let match_timeout = rpc_match_timeout(); - let matched = self.wait_for_request_match(match_timeout); - if debug_enabled { - tracing::debug!( - target: "booster_sdk::rpc", - service_topic = %self.service_topic, - matched, - match_wait_ms = match_timeout.as_millis(), - "rpc request writer match status" - ); - } - if !matched { - return Err(RpcError::Timeout { - timeout: match_timeout, - } - .into()); - } - let request_id = Uuid::new_v4().to_string(); let body = body.into(); let header = serde_json::json!({ "api_id": api_id }).to_string(); From 722d76a0c134bfabbb52725910d2252dcb6c1354 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 22:18:59 +0100 Subject: [PATCH 08/13] Consistent startup wait settings for all rpc clients --- booster_sdk/examples/x5_camera_rpc_check.rs | 90 --------------------- booster_sdk/src/client/ai.rs | 12 +++ booster_sdk/src/client/light_control.rs | 9 +++ booster_sdk/src/client/loco.rs | 9 ++- booster_sdk/src/client/vision.rs | 9 +++ booster_sdk/src/client/x5_camera.rs | 9 +++ booster_sdk/src/dds/rpc.rs | 40 +++++++++ 7 files changed, 87 insertions(+), 91 deletions(-) delete mode 100644 booster_sdk/examples/x5_camera_rpc_check.rs diff --git a/booster_sdk/examples/x5_camera_rpc_check.rs b/booster_sdk/examples/x5_camera_rpc_check.rs deleted file mode 100644 index 356b283..0000000 --- a/booster_sdk/examples/x5_camera_rpc_check.rs +++ /dev/null @@ -1,90 +0,0 @@ -//! Quick X5 camera RPC connectivity check. -//! -//! Run with: -//! `cargo run -p booster_sdk --example x5_camera_rpc_check` -//! -//! Optional env vars: -//! - `BOOSTER_DOMAIN_ID` (default: `0`) -//! - `BOOSTER_TIMEOUT_MS` (default: `3000`) -//! - `BOOSTER_STARTUP_WAIT_MS` (default: `7000`) -//! - `BOOSTER_RETRIES` (default: `3`) -//! - `BOOSTER_RPC_DEBUG` (`1`/`true` for verbose RPC logs) - -use std::time::{Duration, Instant}; - -use booster_sdk::client::x5_camera::X5CameraClient; -use booster_sdk::dds::{RpcClientOptions, X5_CAMERA_CONTROL_API_TOPIC}; - -#[tokio::main] -async fn main() -> Result<(), Box> { - let env_filter = tracing_subscriber::EnvFilter::try_from_default_env() - .unwrap_or_else(|_| tracing_subscriber::EnvFilter::new("error")); - tracing_subscriber::fmt().with_env_filter(env_filter).init(); - - let domain_id = std::env::var("BOOSTER_DOMAIN_ID") - .ok() - .and_then(|v| v.parse::().ok()) - .unwrap_or(0); - let timeout_ms = std::env::var("BOOSTER_TIMEOUT_MS") - .ok() - .and_then(|v| v.parse::().ok()) - .unwrap_or(3000); - let startup_wait_ms = std::env::var("BOOSTER_STARTUP_WAIT_MS") - .ok() - .and_then(|v| v.parse::().ok()) - .unwrap_or(7000); - let retries = std::env::var("BOOSTER_RETRIES") - .ok() - .and_then(|v| v.parse::().ok()) - .unwrap_or(3); - - println!( - "X5 RPC check: domain_id={}, timeout_ms={}, startup_wait_ms={}, retries={}, topic={}", - domain_id, timeout_ms, startup_wait_ms, retries, X5_CAMERA_CONTROL_API_TOPIC - ); - - let client = X5CameraClient::with_options(RpcClientOptions { - domain_id, - default_timeout: Duration::from_millis(timeout_ms), - service_topic: X5_CAMERA_CONTROL_API_TOPIC.to_owned(), - })?; - - // Mimic "waiting for service to become available" before first call. - tokio::time::sleep(Duration::from_millis(startup_wait_ms)).await; - - let total_started = Instant::now(); - let mut last_err = None; - for attempt in 1..=retries { - let started = Instant::now(); - match client.get_status().await { - Ok(resp) => { - let elapsed = started.elapsed(); - let total_elapsed = total_started.elapsed(); - println!( - "OK: attempt={} status={} status_enum={:?} elapsed_ms={} total_elapsed_ms={}", - attempt, - resp.status, - resp.status_enum(), - elapsed.as_millis(), - total_elapsed.as_millis() - ); - return Ok(()); - } - Err(err) => { - let elapsed = started.elapsed(); - eprintln!("attempt {} failed: {} (elapsed_ms={})", attempt, err, elapsed.as_millis()); - last_err = Some(err.to_string()); - if attempt < retries { - tokio::time::sleep(Duration::from_millis(1000)).await; - } - } - } - } - - eprintln!( - "ERR: {}", - last_err.unwrap_or_else(|| "unknown error".to_string()) - ); - eprintln!("total_elapsed_ms={}", total_started.elapsed().as_millis()); - std::process::exit(2); -} diff --git a/booster_sdk/src/client/ai.rs b/booster_sdk/src/client/ai.rs index 410de65..c690355 100644 --- a/booster_sdk/src/client/ai.rs +++ b/booster_sdk/src/client/ai.rs @@ -1,5 +1,7 @@ //! AI and LUI high-level RPC clients. +use std::time::Duration; + use serde::{Deserialize, Serialize}; use crate::dds::{ @@ -113,6 +115,11 @@ impl AiClient { Self::with_options(RpcClientOptions::for_service(AI_API_TOPIC)) } + /// Create an AI client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options(RpcClientOptions::for_service(AI_API_TOPIC).with_startup_wait(startup_wait)) + } + /// Create an AI client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::for_topic(options, AI_API_TOPIC)?; @@ -166,6 +173,11 @@ impl LuiClient { Self::with_options(RpcClientOptions::for_service(LUI_API_TOPIC)) } + /// Create a LUI client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options(RpcClientOptions::for_service(LUI_API_TOPIC).with_startup_wait(startup_wait)) + } + /// Create a LUI client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::for_topic(options, LUI_API_TOPIC)?; diff --git a/booster_sdk/src/client/light_control.rs b/booster_sdk/src/client/light_control.rs index eebe612..2b66e47 100644 --- a/booster_sdk/src/client/light_control.rs +++ b/booster_sdk/src/client/light_control.rs @@ -1,5 +1,7 @@ //! LED light control RPC client. +use std::time::Duration; + use serde::{Deserialize, Serialize}; use crate::dds::{LIGHT_CONTROL_API_TOPIC, RpcClient, RpcClientOptions}; @@ -49,6 +51,13 @@ impl LightControlClient { Self::with_options(RpcClientOptions::for_service(LIGHT_CONTROL_API_TOPIC)) } + /// Create a light control client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options( + RpcClientOptions::for_service(LIGHT_CONTROL_API_TOPIC).with_startup_wait(startup_wait), + ) + } + /// Create a light control client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::for_topic(options, LIGHT_CONTROL_API_TOPIC)?; diff --git a/booster_sdk/src/client/loco.rs b/booster_sdk/src/client/loco.rs index de3a922..ae19711 100644 --- a/booster_sdk/src/client/loco.rs +++ b/booster_sdk/src/client/loco.rs @@ -1,5 +1,7 @@ //! High-level B1 locomotion client built on DDS RPC and topic I/O. +use std::time::Duration; + use crate::dds::{ BatteryState, BinaryData, ButtonEventMsg, DdsNode, DdsPublisher, DdsSubscription, GripperControl, LightControlMsg, MotionState, RemoteControllerState, RobotProcessStateMsg, @@ -21,7 +23,7 @@ use typed_builder::TypedBuilder; // The controller may send an intermediate pending status (-1) before the // final success response. Mode transitions (especially PREPARE) can take // several seconds. -const CHANGE_MODE_TIMEOUT: std::time::Duration = std::time::Duration::from_secs(30); +const CHANGE_MODE_TIMEOUT: Duration = Duration::from_secs(30); /// High-level client for B1 locomotion control and telemetry. pub struct BoosterClient { @@ -37,6 +39,11 @@ impl BoosterClient { Self::with_options(RpcClientOptions::default()) } + /// Create a locomotion client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options(RpcClientOptions::default().with_startup_wait(startup_wait)) + } + /// Create a locomotion client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::new(options)?; diff --git a/booster_sdk/src/client/vision.rs b/booster_sdk/src/client/vision.rs index 76c4c95..ba853fb 100644 --- a/booster_sdk/src/client/vision.rs +++ b/booster_sdk/src/client/vision.rs @@ -1,5 +1,7 @@ //! Vision service RPC client. +use std::time::Duration; + use serde::{Deserialize, Serialize}; use serde_json::Value; @@ -59,6 +61,13 @@ impl VisionClient { Self::with_options(RpcClientOptions::for_service(VISION_API_TOPIC)) } + /// Create a vision client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options( + RpcClientOptions::for_service(VISION_API_TOPIC).with_startup_wait(startup_wait), + ) + } + /// Create a vision client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::for_topic(options, VISION_API_TOPIC)?; diff --git a/booster_sdk/src/client/x5_camera.rs b/booster_sdk/src/client/x5_camera.rs index 294a818..255c084 100644 --- a/booster_sdk/src/client/x5_camera.rs +++ b/booster_sdk/src/client/x5_camera.rs @@ -1,5 +1,7 @@ //! X5 camera control RPC client. +use std::time::Duration; + use serde::{Deserialize, Serialize}; use crate::dds::{RpcClient, RpcClientOptions, X5_CAMERA_CONTROL_API_TOPIC}; @@ -64,6 +66,13 @@ impl X5CameraClient { Self::with_options(RpcClientOptions::for_service(X5_CAMERA_CONTROL_API_TOPIC)) } + /// Create an X5 camera client with a custom startup wait before first RPC. + pub fn with_startup_wait(startup_wait: Duration) -> Result { + Self::with_options( + RpcClientOptions::for_service(X5_CAMERA_CONTROL_API_TOPIC).with_startup_wait(startup_wait), + ) + } + /// Create an X5 camera client with custom RPC options. pub fn with_options(options: RpcClientOptions) -> Result { let rpc = RpcClient::for_topic(options, X5_CAMERA_CONTROL_API_TOPIC)?; diff --git a/booster_sdk/src/dds/rpc.rs b/booster_sdk/src/dds/rpc.rs index af881cd..c5542ad 100644 --- a/booster_sdk/src/dds/rpc.rs +++ b/booster_sdk/src/dds/rpc.rs @@ -2,6 +2,7 @@ use serde::{Deserialize, Serialize, de::DeserializeOwned}; use serde_json::Value; +use std::sync::atomic::{AtomicBool, Ordering}; use std::time::{Duration, Instant}; use uuid::Uuid; @@ -18,6 +19,7 @@ use super::topics::{LOCO_API_TOPIC, rpc_request_topic, rpc_response_topic}; pub struct RpcClientOptions { pub domain_id: u16, pub default_timeout: Duration, + pub startup_wait: Duration, pub service_topic: String, } @@ -28,6 +30,8 @@ impl Default for RpcClientOptions { // 5 s is a safe default for most commands. Mode changes are slow, // so change_mode passes its own longer timeout. default_timeout: Duration::from_secs(5), + // Wait once before the first RPC call so endpoint discovery can settle. + startup_wait: Duration::from_millis(3000), service_topic: LOCO_API_TOPIC.to_owned(), } } @@ -47,6 +51,23 @@ impl RpcClientOptions { self.service_topic = service_topic.into(); self } + + #[must_use] + pub fn with_default_timeout(mut self, timeout: Duration) -> Self { + self.default_timeout = timeout; + self + } + + #[must_use] + pub fn with_startup_wait(mut self, startup_wait: Duration) -> Self { + self.startup_wait = startup_wait; + self + } + + #[must_use] + pub fn without_startup_wait(self) -> Self { + self.with_startup_wait(Duration::from_millis(0)) + } } pub struct RpcClient { @@ -54,6 +75,8 @@ pub struct RpcClient { request_writer: rustdds::no_key::DataWriter, response_reader: Arc>>, default_timeout: Duration, + startup_wait: Duration, + startup_wait_done: AtomicBool, service_topic: String, } @@ -148,6 +171,8 @@ impl RpcClient { request_writer: request_writer.into_inner(), response_reader: Arc::new(Mutex::new(response_reader)), default_timeout: options.default_timeout, + startup_wait: options.startup_wait, + startup_wait_done: AtomicBool::new(false), service_topic, }) } @@ -229,6 +254,21 @@ impl RpcClient { R: DeserializeOwned + Send + 'static, { let debug_enabled = rpc_debug_enabled(); + + if self.startup_wait > Duration::from_millis(0) + && !self.startup_wait_done.swap(true, Ordering::SeqCst) + { + if debug_enabled { + tracing::debug!( + target: "booster_sdk::rpc", + service_topic = %self.service_topic, + startup_wait_ms = self.startup_wait.as_millis(), + "initial startup wait before first rpc call" + ); + } + std::thread::sleep(self.startup_wait); + } + let request_id = Uuid::new_v4().to_string(); let body = body.into(); let header = serde_json::json!({ "api_id": api_id }).to_string(); From 418ebb61a947b2022fc4da470a6ac4771e68eb29 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 22:43:01 +0100 Subject: [PATCH 09/13] add support for startup wait config to python api --- .../booster_sdk_bindings.pyi | 12 ++++++------ booster_sdk_py/src/client/ai.rs | 14 +++++++++++--- booster_sdk_py/src/client/booster.rs | 14 +++++++++++--- booster_sdk_py/src/client/light_control.rs | 14 +++++++++++--- booster_sdk_py/src/client/lui.rs | 14 +++++++++++--- booster_sdk_py/src/client/vision.rs | 14 +++++++++++--- booster_sdk_py/src/client/x5_camera.rs | 14 +++++++++++--- booster_sdk_py/src/lib.rs | 18 +++++++++++++++++- 8 files changed, 89 insertions(+), 25 deletions(-) diff --git a/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi b/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi index db202c9..46c5f42 100644 --- a/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi +++ b/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi @@ -454,7 +454,7 @@ class DetectResults: def rgb_mean(self) -> list[int]: ... class BoosterClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def change_mode(self, mode: RobotMode) -> None: ... def get_mode(self) -> GetModeResponse: ... def get_status(self) -> GetStatusResponse: ... @@ -537,7 +537,7 @@ class BoosterClient: ) -> None: ... class AiClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def start_ai_chat(self, param: StartAiChatParameter) -> None: ... def stop_ai_chat(self) -> None: ... def speak(self, param: SpeakParameter) -> None: ... @@ -545,7 +545,7 @@ class AiClient: def stop_face_tracking(self) -> None: ... class LuiClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def start_asr(self) -> None: ... def stop_asr(self) -> None: ... def start_tts(self, config: LuiTtsConfig) -> None: ... @@ -553,12 +553,12 @@ class LuiClient: def send_tts_text(self, param: LuiTtsParameter) -> None: ... class LightControlClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def set_led_light_color(self, r: int, g: int, b: int) -> None: ... def stop_led_light_control(self) -> None: ... class VisionClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def start_vision_service( self, enable_position: bool, @@ -572,6 +572,6 @@ class VisionClient: def get_detection_object(self) -> list[DetectResults]: ... class X5CameraClient: - def __init__(self) -> None: ... + def __init__(self, startup_wait_sec: float | None = ...) -> None: ... def change_mode(self, mode: CameraSetMode) -> None: ... def get_status(self) -> X5CameraGetStatusResponse: ... diff --git a/booster_sdk_py/src/client/ai.rs b/booster_sdk_py/src/client/ai.rs index 62086c2..2ef9028 100644 --- a/booster_sdk_py/src/client/ai.rs +++ b/booster_sdk_py/src/client/ai.rs @@ -5,7 +5,7 @@ use booster_sdk::client::ai::{ }; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass(module = "booster_sdk_bindings", name = "TtsConfig")] #[derive(Clone)] @@ -192,9 +192,17 @@ pub struct PyAiClient { #[pymethods] impl PyAiClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => AiClient::with_startup_wait(wait), + None => AiClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(AiClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/client/booster.rs b/booster_sdk_py/src/client/booster.rs index 001799c..27487b2 100644 --- a/booster_sdk_py/src/client/booster.rs +++ b/booster_sdk_py/src/client/booster.rs @@ -12,7 +12,7 @@ use booster_sdk::{ }; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass(module = "booster_sdk_bindings", name = "RobotMode", eq)] #[derive(Clone, Copy, PartialEq, Eq)] @@ -1268,9 +1268,17 @@ pub struct PyBoosterClient { #[pymethods] impl PyBoosterClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => BoosterClient::with_startup_wait(wait), + None => BoosterClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(BoosterClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/client/light_control.rs b/booster_sdk_py/src/client/light_control.rs index 5517a3e..5780961 100644 --- a/booster_sdk_py/src/client/light_control.rs +++ b/booster_sdk_py/src/client/light_control.rs @@ -3,7 +3,7 @@ use std::sync::Arc; use booster_sdk::client::light_control::LightControlClient; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass( module = "booster_sdk_bindings", @@ -17,9 +17,17 @@ pub struct PyLightControlClient { #[pymethods] impl PyLightControlClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => LightControlClient::with_startup_wait(wait), + None => LightControlClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(LightControlClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/client/lui.rs b/booster_sdk_py/src/client/lui.rs index d00504c..85ad4dc 100644 --- a/booster_sdk_py/src/client/lui.rs +++ b/booster_sdk_py/src/client/lui.rs @@ -3,7 +3,7 @@ use std::sync::Arc; use booster_sdk::client::ai::{LuiClient, LuiTtsConfig, LuiTtsParameter}; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass(module = "booster_sdk_bindings", name = "LuiTtsConfig")] #[derive(Clone)] @@ -59,9 +59,17 @@ pub struct PyLuiClient { #[pymethods] impl PyLuiClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => LuiClient::with_startup_wait(wait), + None => LuiClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(LuiClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/client/vision.rs b/booster_sdk_py/src/client/vision.rs index 691776c..01cc448 100644 --- a/booster_sdk_py/src/client/vision.rs +++ b/booster_sdk_py/src/client/vision.rs @@ -3,7 +3,7 @@ use std::sync::Arc; use booster_sdk::client::vision::{DetectResults, VisionClient}; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass(module = "booster_sdk_bindings", name = "DetectResults")] #[derive(Clone)] @@ -97,9 +97,17 @@ pub struct PyVisionClient { #[pymethods] impl PyVisionClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => VisionClient::with_startup_wait(wait), + None => VisionClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(VisionClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/client/x5_camera.rs b/booster_sdk_py/src/client/x5_camera.rs index 8f4b091..f7ff2da 100644 --- a/booster_sdk_py/src/client/x5_camera.rs +++ b/booster_sdk_py/src/client/x5_camera.rs @@ -5,7 +5,7 @@ use booster_sdk::client::x5_camera::{ }; use pyo3::{Bound, prelude::*, types::PyModule}; -use crate::{runtime::wait_for_future, to_py_err}; +use crate::{runtime::wait_for_future, startup_wait_from_seconds, to_py_err}; #[pyclass(module = "booster_sdk_bindings", name = "CameraSetMode", eq)] #[derive(Clone, Copy, PartialEq, Eq)] @@ -132,9 +132,17 @@ pub struct PyX5CameraClient { #[pymethods] impl PyX5CameraClient { #[new] - fn new() -> PyResult { + #[pyo3(signature = (startup_wait_sec=None))] + fn new(startup_wait_sec: Option) -> PyResult { + let startup_wait = startup_wait_from_seconds(startup_wait_sec)?; + let client = match startup_wait { + Some(wait) => X5CameraClient::with_startup_wait(wait), + None => X5CameraClient::new(), + } + .map_err(to_py_err)?; + Ok(Self { - client: Arc::new(X5CameraClient::new().map_err(to_py_err)?), + client: Arc::new(client), }) } diff --git a/booster_sdk_py/src/lib.rs b/booster_sdk_py/src/lib.rs index 48d8f8b..48e200a 100644 --- a/booster_sdk_py/src/lib.rs +++ b/booster_sdk_py/src/lib.rs @@ -1,10 +1,11 @@ mod client; mod runtime; +use std::time::Duration; use std::sync::OnceLock; use booster_sdk::{client::ai::BOOSTER_ROBOT_USER_ID, types::BoosterError}; -use pyo3::{exceptions::PyException, prelude::*, types::PyModule}; +use pyo3::{exceptions::{PyException, PyValueError}, prelude::*, types::PyModule}; use tracing_subscriber::{EnvFilter, fmt}; pyo3::create_exception!(booster_sdk_bindings, BoosterSdkError, PyException); @@ -13,6 +14,21 @@ pub(crate) fn to_py_err(err: BoosterError) -> PyErr { BoosterSdkError::new_err(err.to_string()) } +pub(crate) fn startup_wait_from_seconds(startup_wait_sec: Option) -> PyResult> { + let Some(seconds) = startup_wait_sec else { + return Ok(None); + }; + + if !seconds.is_finite() { + return Err(PyValueError::new_err("startup_wait_sec must be finite")); + } + if seconds < 0.0 { + return Err(PyValueError::new_err("startup_wait_sec must be >= 0")); + } + + Ok(Some(Duration::from_secs_f64(seconds))) +} + fn rpc_debug_enabled() -> bool { std::env::var("BOOSTER_RPC_DEBUG") .map(|value| { From 32e828e8a180eaa0b69ba314318b02668b73a1a3 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 23:02:39 +0100 Subject: [PATCH 10/13] add docs to sdk bindings! --- booster_sdk/src/client/x5_camera.rs | 3 +- .../booster_sdk_bindings.pyi | 1109 +++++++++++++---- 2 files changed, 866 insertions(+), 246 deletions(-) diff --git a/booster_sdk/src/client/x5_camera.rs b/booster_sdk/src/client/x5_camera.rs index 255c084..038cdcf 100644 --- a/booster_sdk/src/client/x5_camera.rs +++ b/booster_sdk/src/client/x5_camera.rs @@ -69,7 +69,8 @@ impl X5CameraClient { /// Create an X5 camera client with a custom startup wait before first RPC. pub fn with_startup_wait(startup_wait: Duration) -> Result { Self::with_options( - RpcClientOptions::for_service(X5_CAMERA_CONTROL_API_TOPIC).with_startup_wait(startup_wait), + RpcClientOptions::for_service(X5_CAMERA_CONTROL_API_TOPIC) + .with_startup_wait(startup_wait), ) } diff --git a/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi b/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi index 46c5f42..984a8b1 100644 --- a/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi +++ b/booster_sdk_py/booster_sdk_bindings/booster_sdk_bindings.pyi @@ -10,6 +10,13 @@ class BoosterSdkError(Exception): ... class RobotMode: + """Operational robot modes used by locomotion APIs. + + Use these values with :meth:`BoosterClient.change_mode` and + :meth:`BoosterClient.get_up_with_mode`. The integer representation is the + raw RPC value returned by the robot service. + """ + UNKNOWN: RobotMode DAMPING: RobotMode PREPARE: RobotMode @@ -17,35 +24,71 @@ class RobotMode: CUSTOM: RobotMode SOCCER: RobotMode - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same mode.""" + ... class Hand: + """Hand selector used by arm, gripper, and dexterous-hand APIs.""" + LEFT: Hand RIGHT: Hand - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same hand.""" + ... class GripperMode: + """Control mode for gripper commands. + + ``POSITION`` interprets ``motion_param`` as target opening. + ``FORCE`` interprets ``motion_param`` as grasp force. + """ + POSITION: GripperMode FORCE: GripperMode - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same mode.""" + ... class HandAction: + """Open/close hand action used by handshake and wave APIs.""" + OPEN: HandAction CLOSE: HandAction - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same action.""" + ... class Frame: + """Reference frame identifiers used for transform queries.""" + UNKNOWN: Frame BODY: Frame HEAD: Frame @@ -54,29 +97,53 @@ class Frame: LEFT_FOOT: Frame RIGHT_FOOT: Frame - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same frame.""" + ... class GripperControlMode: + """Mode for :meth:`BoosterClient.control_gripper`.""" + POSITION: GripperControlMode FORCE: GripperControlMode - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same mode.""" + ... class BoosterHandType: + """Dexterous hand hardware type used by low-level hand control APIs.""" + INSPIRE_HAND: BoosterHandType INSPIRE_TOUCH_HAND: BoosterHandType REVO_HAND: BoosterHandType UNKNOWN: BoosterHandType - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same hand type.""" + ... class DanceId: + """Upper-body dance and gesture identifiers for :meth:`BoosterClient.dance`.""" + NEW_YEAR: DanceId NEZHA: DanceId TOWARDS_FUTURE: DanceId @@ -87,11 +154,19 @@ class DanceId: LUCKY_CAT_GESTURE: DanceId STOP: DanceId - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same dance id.""" + ... class WholeBodyDanceId: + """Whole-body dance identifiers for :meth:`BoosterClient.whole_body_dance`.""" + ARBIC_DANCE: WholeBodyDanceId MICHAEL_DANCE_1: WholeBodyDanceId MICHAEL_DANCE_2: WholeBodyDanceId @@ -100,19 +175,35 @@ class WholeBodyDanceId: BOXING_STYLE_KICK: WholeBodyDanceId ROUNDHOUSE_KICK: WholeBodyDanceId - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same dance id.""" + ... class JointOrder: + """Joint indexing convention used by custom trajectory models.""" + MUJOCO: JointOrder ISAAC_LAB: JointOrder - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same joint order.""" + ... class BodyControl: + """High-level body-control state values reported by ``get_status()``.""" + UNKNOWN: BodyControl DAMPING: BodyControl PREPARE: BodyControl @@ -127,11 +218,19 @@ class BodyControl: GOALIE: BodyControl WBC_GAIT: BodyControl - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same body state.""" + ... class Action: + """High-level action identifiers reported by ``get_status()``.""" + UNKNOWN: Action HAND_SHAKE: Action HAND_WAVE: Action @@ -149,193 +248,370 @@ class Action: RECORD_TRAJ: Action RUN_RECORDED_TRAJ: Action - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same action.""" + ... class CameraSetMode: + """Requested X5 camera mode for :meth:`X5CameraClient.change_mode`.""" + CAMERA_MODE_NORMAL: CameraSetMode CAMERA_MODE_HIGH_RESOLUTION: CameraSetMode CAMERA_MODE_NORMAL_ENABLE: CameraSetMode CAMERA_MODE_HIGH_RESOLUTION_ENABLE: CameraSetMode - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same mode.""" + ... class CameraControlStatus: + """Status values reported by :meth:`X5CameraClient.get_status`.""" + CAMERA_STATUS_NORMAL: CameraControlStatus CAMERA_STATUS_HIGH_RESOLUTION: CameraControlStatus CAMERA_STATUS_ERROR: CameraControlStatus CAMERA_STATUS_NULL: CameraControlStatus - def __repr__(self) -> str: ... - def __int__(self) -> int: ... - def __eq__(self, other: object) -> bool: ... + def __repr__(self) -> str: + """Return a stable enum-style representation.""" + ... + def __int__(self) -> int: + """Return the raw integer value used by the RPC API.""" + ... + def __eq__(self, other: object) -> bool: + """Return ``True`` when both values represent the same status.""" + ... class GripperCommand: + """High-level gripper command payload used for topic publishing.""" def __init__( self, hand: Hand, mode: GripperMode, motion_param: int, speed: int | None = ..., - ) -> None: ... + ) -> None: + """Create a gripper command. + + Args: + hand: Target hand. + mode: Command mode (position or force). + motion_param: Position or force value depending on ``mode``. + speed: Motion speed (default: ``500``). + """ + ... @staticmethod - def open(hand: Hand) -> GripperCommand: ... + def open(hand: Hand) -> GripperCommand: + """Build a position-mode command that fully opens the gripper.""" + ... @staticmethod - def close(hand: Hand) -> GripperCommand: ... + def close(hand: Hand) -> GripperCommand: + """Build a position-mode command that fully closes the gripper.""" + ... @staticmethod - def grasp(hand: Hand, force: int) -> GripperCommand: ... - @property - def hand(self) -> Hand: ... - @property - def mode(self) -> GripperMode: ... - @property - def motion_param(self) -> int: ... - @property - def speed(self) -> int: ... - def __repr__(self) -> str: ... + def grasp(hand: Hand, force: int) -> GripperCommand: + """Build a force-mode grasp command. + + ``force`` is clamped to the SDK-supported range ``[50, 1000]``. + """ + ... + @property + def hand(self) -> Hand: + """Target hand.""" + ... + @property + def mode(self) -> GripperMode: + """Command mode.""" + ... + @property + def motion_param(self) -> int: + """Position/force parameter interpreted by ``mode``.""" + ... + @property + def speed(self) -> int: + """Command speed value.""" + ... + def __repr__(self) -> str: + """Return a debug representation of this command.""" + ... class Position: - def __init__(self, x: float, y: float, z: float) -> None: ... - @property - def x(self) -> float: ... + """Cartesian position in the robot coordinate system.""" + def __init__(self, x: float, y: float, z: float) -> None: + """Create a position from ``x``, ``y``, and ``z`` coordinates.""" + ... + @property + def x(self) -> float: + """X coordinate.""" + ... @x.setter - def x(self, value: float) -> None: ... + def x(self, value: float) -> None: + """Set the X coordinate.""" + ... @property - def y(self) -> float: ... + def y(self) -> float: + """Y coordinate.""" + ... @y.setter - def y(self, value: float) -> None: ... + def y(self, value: float) -> None: + """Set the Y coordinate.""" + ... @property - def z(self) -> float: ... + def z(self) -> float: + """Z coordinate.""" + ... @z.setter - def z(self, value: float) -> None: ... + def z(self, value: float) -> None: + """Set the Z coordinate.""" + ... class Orientation: - def __init__(self, roll: float, pitch: float, yaw: float) -> None: ... - @property - def roll(self) -> float: ... + """Euler orientation (roll, pitch, yaw) in radians.""" + def __init__(self, roll: float, pitch: float, yaw: float) -> None: + """Create an orientation from roll, pitch, and yaw angles.""" + ... + @property + def roll(self) -> float: + """Roll angle in radians.""" + ... @roll.setter - def roll(self, value: float) -> None: ... + def roll(self, value: float) -> None: + """Set roll angle in radians.""" + ... @property - def pitch(self) -> float: ... + def pitch(self) -> float: + """Pitch angle in radians.""" + ... @pitch.setter - def pitch(self, value: float) -> None: ... + def pitch(self, value: float) -> None: + """Set pitch angle in radians.""" + ... @property - def yaw(self) -> float: ... + def yaw(self) -> float: + """Yaw angle in radians.""" + ... @yaw.setter - def yaw(self, value: float) -> None: ... + def yaw(self, value: float) -> None: + """Set yaw angle in radians.""" + ... class Posture: - def __init__(self, position: Position, orientation: Orientation) -> None: ... - @property - def position(self) -> Position: ... + """Combined position and Euler orientation target.""" + def __init__(self, position: Position, orientation: Orientation) -> None: + """Create a posture from ``position`` and ``orientation``.""" + ... + @property + def position(self) -> Position: + """Position component.""" + ... @position.setter - def position(self, value: Position) -> None: ... + def position(self, value: Position) -> None: + """Set the position component.""" + ... @property - def orientation(self) -> Orientation: ... + def orientation(self) -> Orientation: + """Orientation component.""" + ... @orientation.setter - def orientation(self, value: Orientation) -> None: ... + def orientation(self, value: Orientation) -> None: + """Set the orientation component.""" + ... class Quaternion: - def __init__(self, x: float, y: float, z: float, w: float) -> None: ... - @property - def x(self) -> float: ... - @property - def y(self) -> float: ... - @property - def z(self) -> float: ... - @property - def w(self) -> float: ... + """Quaternion orientation container.""" + def __init__(self, x: float, y: float, z: float, w: float) -> None: + """Create a quaternion from ``x``, ``y``, ``z``, and ``w`` values.""" + ... + @property + def x(self) -> float: + """Quaternion X component.""" + ... + @property + def y(self) -> float: + """Quaternion Y component.""" + ... + @property + def z(self) -> float: + """Quaternion Z component.""" + ... + @property + def w(self) -> float: + """Quaternion W component.""" + ... class Transform: - def __init__(self, position: Position, orientation: Quaternion) -> None: ... - @property - def position(self) -> Position: ... - @property - def orientation(self) -> Quaternion: ... + """Rigid transform with translation and quaternion orientation.""" + def __init__(self, position: Position, orientation: Quaternion) -> None: + """Create a transform.""" + ... + @property + def position(self) -> Position: + """Translation component.""" + ... + @property + def orientation(self) -> Quaternion: + """Quaternion orientation component.""" + ... class GripperMotionParameter: - def __init__(self, position: int, force: int, speed: int) -> None: ... - @property - def position(self) -> int: ... - @property - def force(self) -> int: ... - @property - def speed(self) -> int: ... + """Parameter bundle for :meth:`BoosterClient.control_gripper`.""" + def __init__(self, position: int, force: int, speed: int) -> None: + """Create gripper motion parameters.""" + ... + @property + def position(self) -> int: + """Target position value.""" + ... + @property + def force(self) -> int: + """Target force value.""" + ... + @property + def speed(self) -> int: + """Motion speed value.""" + ... class DexterousFingerParameter: - def __init__(self, seq: int, angle: int, force: int, speed: int) -> None: ... - @property - def seq(self) -> int: ... - @property - def angle(self) -> int: ... - @property - def force(self) -> int: ... - @property - def speed(self) -> int: ... + """Low-level command for a single dexterous finger.""" + def __init__(self, seq: int, angle: int, force: int, speed: int) -> None: + """Create one dexterous-finger command.""" + ... + @property + def seq(self) -> int: + """Finger sequence/index.""" + ... + @property + def angle(self) -> int: + """Target finger angle.""" + ... + @property + def force(self) -> int: + """Force value for this finger.""" + ... + @property + def speed(self) -> int: + """Speed value for this finger.""" + ... class CustomModelParams: + """Controller gains and scaling for a custom trajectory model.""" def __init__( self, action_scale: list[float], kp: list[float], kd: list[float] - ) -> None: ... + ) -> None: + """Create custom-model parameter vectors.""" + ... @property - def action_scale(self) -> list[float]: ... + def action_scale(self) -> list[float]: + """Per-joint action scaling factors.""" + ... @property - def kp(self) -> list[float]: ... + def kp(self) -> list[float]: + """Per-joint proportional gains.""" + ... @property - def kd(self) -> list[float]: ... + def kd(self) -> list[float]: + """Per-joint derivative gains.""" + ... class CustomModel: + """Metadata for a model used by custom trained trajectories.""" def __init__( self, file_path: str, params: list[CustomModelParams], joint_order: JointOrder, - ) -> None: ... + ) -> None: + """Create a custom model descriptor.""" + ... @property - def file_path(self) -> str: ... + def file_path(self) -> str: + """Path to the model file.""" + ... @property - def params(self) -> list[CustomModelParams]: ... + def params(self) -> list[CustomModelParams]: + """Model parameter sets.""" + ... @property - def joint_order(self) -> JointOrder: ... + def joint_order(self) -> JointOrder: + """Joint indexing convention expected by the model.""" + ... class CustomTrainedTraj: - def __init__(self, traj_file_path: str, model: CustomModel) -> None: ... - @property - def traj_file_path(self) -> str: ... - @property - def model(self) -> CustomModel: ... + """Payload for loading a custom trained trajectory.""" + def __init__(self, traj_file_path: str, model: CustomModel) -> None: + """Create a trajectory payload for ``load_custom_trained_traj``.""" + ... + @property + def traj_file_path(self) -> str: + """Path to the trajectory file.""" + ... + @property + def model(self) -> CustomModel: + """Model metadata associated with this trajectory.""" + ... class TtsConfig: - def __init__(self, voice_type: str, ignore_bracket_text: list[int]) -> None: ... - @property - def voice_type(self) -> str: ... - @property - def ignore_bracket_text(self) -> list[int]: ... + """Text-to-speech configuration for AI chat.""" + def __init__(self, voice_type: str, ignore_bracket_text: list[int]) -> None: + """Create TTS configuration.""" + ... + @property + def voice_type(self) -> str: + """Voice profile identifier.""" + ... + @property + def ignore_bracket_text(self) -> list[int]: + """Service-specific flags for bracket-text filtering.""" + ... class LlmConfig: - def __init__( - self, system_prompt: str, welcome_msg: str, prompt_name: str - ) -> None: ... - @property - def system_prompt(self) -> str: ... - @property - def welcome_msg(self) -> str: ... - @property - def prompt_name(self) -> str: ... + """Prompt configuration for the AI chat LLM.""" + def __init__(self, system_prompt: str, welcome_msg: str, prompt_name: str) -> None: + """Create LLM prompt configuration.""" + ... + @property + def system_prompt(self) -> str: + """System instruction prompt.""" + ... + @property + def welcome_msg(self) -> str: + """Initial assistant greeting.""" + ... + @property + def prompt_name(self) -> str: + """Prompt template/profile name.""" + ... class AsrConfig: + """Automatic speech recognition interruption settings.""" def __init__( self, interrupt_speech_duration: int, interrupt_keywords: list[str] - ) -> None: ... + ) -> None: + """Create ASR interruption configuration.""" + ... @property - def interrupt_speech_duration(self) -> int: ... + def interrupt_speech_duration(self) -> int: + """Interruption speech duration threshold used by the service.""" + ... @property - def interrupt_keywords(self) -> list[str]: ... + def interrupt_keywords(self) -> list[str]: + """Keywords that trigger interruption behavior.""" + ... class StartAiChatParameter: + """Configuration payload for :meth:`AiClient.start_ai_chat`.""" def __init__( self, interrupt_mode: bool, @@ -343,57 +619,118 @@ class StartAiChatParameter: llm_config: LlmConfig, tts_config: TtsConfig, enable_face_tracking: bool, - ) -> None: ... + ) -> None: + """Create AI chat startup parameters.""" + ... @property - def interrupt_mode(self) -> bool: ... + def interrupt_mode(self) -> bool: + """Whether interruption mode is enabled.""" + ... @property - def asr_config(self) -> AsrConfig: ... + def asr_config(self) -> AsrConfig: + """ASR configuration.""" + ... @property - def llm_config(self) -> LlmConfig: ... + def llm_config(self) -> LlmConfig: + """LLM prompt configuration.""" + ... @property - def tts_config(self) -> TtsConfig: ... + def tts_config(self) -> TtsConfig: + """TTS configuration.""" + ... @property - def enable_face_tracking(self) -> bool: ... + def enable_face_tracking(self) -> bool: + """Whether AI face tracking should start with chat.""" + ... class SpeakParameter: - def __init__(self, msg: str) -> None: ... - @property - def msg(self) -> str: ... + """Payload for :meth:`AiClient.speak`.""" + def __init__(self, msg: str) -> None: + """Create a speech request with plain text content.""" + ... + @property + def msg(self) -> str: + """Text that should be spoken by the AI service.""" + ... class LuiTtsConfig: - def __init__(self, voice_type: str) -> None: ... - @property - def voice_type(self) -> str: ... + """TTS startup configuration for :class:`LuiClient`.""" + def __init__(self, voice_type: str) -> None: + """Create LUI TTS configuration.""" + ... + @property + def voice_type(self) -> str: + """Voice profile identifier.""" + ... class LuiTtsParameter: - def __init__(self, text: str) -> None: ... - @property - def text(self) -> str: ... + """Payload for :meth:`LuiClient.send_tts_text`.""" + def __init__(self, text: str) -> None: + """Create a TTS text payload.""" + ... + @property + def text(self) -> str: + """Text to synthesize via the LUI service.""" + ... class GetModeResponse: - def __init__(self, mode: int) -> None: ... + """Response payload returned by ``BoosterClient.get_mode()``.""" + + def __init__(self, mode: int) -> None: + """Create a mode response from raw integer mode.""" + ... + @property - def mode(self) -> int: ... - def mode_enum(self) -> RobotMode | None: ... + def mode(self) -> int: + """Raw robot mode value.""" + ... + + def mode_enum(self) -> RobotMode | None: + """Mode converted to ``RobotMode`` when known, else ``None``.""" + ... class GetStatusResponse: + """Response payload returned by ``BoosterClient.get_status()``.""" + def __init__( self, current_mode: int, current_body_control: int, current_actions: list[int], - ) -> None: ... + ) -> None: + """Create a status response from raw integer fields.""" + ... + @property - def current_mode(self) -> int: ... + def current_mode(self) -> int: + """Raw current mode value.""" + ... + @property - def current_body_control(self) -> int: ... + def current_body_control(self) -> int: + """Raw current body-control state value.""" + ... + @property - def current_actions(self) -> list[int]: ... - def current_mode_enum(self) -> RobotMode | None: ... - def current_body_control_enum(self) -> BodyControl | None: ... - def current_actions_enum(self) -> list[Action]: ... + def current_actions(self) -> list[int]: + """Raw list of active action identifiers.""" + ... + + def current_mode_enum(self) -> RobotMode | None: + """Current mode converted to ``RobotMode`` when known.""" + ... + + def current_body_control_enum(self) -> BodyControl | None: + """Body control converted to ``BodyControl`` when known.""" + ... + + def current_actions_enum(self) -> list[Action]: + """Active actions converted to known ``Action`` values.""" + ... class GetRobotInfoResponse: + """Robot identity and firmware metadata response.""" + def __init__( self, name: str, @@ -401,30 +738,66 @@ class GetRobotInfoResponse: version: str, model: str, serial_number: str, - ) -> None: ... + ) -> None: + """Create robot info payload.""" + ... + @property - def name(self) -> str: ... + def name(self) -> str: + """Robot name.""" + ... + @property - def nickname(self) -> str: ... + def nickname(self) -> str: + """User-configured nickname.""" + ... + @property - def version(self) -> str: ... + def version(self) -> str: + """Software/firmware version string.""" + ... + @property - def model(self) -> str: ... + def model(self) -> str: + """Robot model identifier.""" + ... + @property - def serial_number(self) -> str: ... + def serial_number(self) -> str: + """Hardware serial number.""" + ... class LoadCustomTrainedTrajResponse: - def __init__(self, tid: str) -> None: ... + """Response for ``load_custom_trained_traj`` containing trajectory id.""" + + def __init__(self, tid: str) -> None: + """Create trajectory-load response.""" + ... + @property - def tid(self) -> str: ... + def tid(self) -> str: + """Loaded trajectory identifier used by activate/unload APIs.""" + ... class X5CameraGetStatusResponse: - def __init__(self, status: int) -> None: ... + """Response payload returned by ``X5CameraClient.get_status()``.""" + + def __init__(self, status: int) -> None: + """Create camera status response from raw status integer.""" + ... + @property - def status(self) -> int: ... - def status_enum(self) -> CameraControlStatus | None: ... + def status(self) -> int: + """Raw camera status value.""" + ... + + def status_enum(self) -> CameraControlStatus | None: + """Status converted to ``CameraControlStatus`` when known.""" + ... class DetectResults: + """Single detection result produced by the vision service.""" + def __init__( self, xmin: int, @@ -435,143 +808,389 @@ class DetectResults: tag: str, conf: float, rgb_mean: list[int], - ) -> None: ... + ) -> None: + """Create a detection record.""" + ... + @property - def xmin(self) -> int: ... + def xmin(self) -> int: + """Left pixel coordinate of bounding box.""" + ... + @property - def ymin(self) -> int: ... + def ymin(self) -> int: + """Top pixel coordinate of bounding box.""" + ... + @property - def xmax(self) -> int: ... + def xmax(self) -> int: + """Right pixel coordinate of bounding box.""" + ... + @property - def ymax(self) -> int: ... + def ymax(self) -> int: + """Bottom pixel coordinate of bounding box.""" + ... + @property - def position(self) -> list[float]: ... + def position(self) -> list[float]: + """Estimated position vector for the detection.""" + ... + @property - def tag(self) -> str: ... + def tag(self) -> str: + """Detected class/tag label.""" + ... + @property - def conf(self) -> float: ... + def conf(self) -> float: + """Detection confidence score.""" + ... + @property - def rgb_mean(self) -> list[int]: ... + def rgb_mean(self) -> list[int]: + """Mean RGB values over the detection region.""" + ... class BoosterClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... - def change_mode(self, mode: RobotMode) -> None: ... - def get_mode(self) -> GetModeResponse: ... - def get_status(self) -> GetStatusResponse: ... - def get_robot_info(self) -> GetRobotInfoResponse: ... - def move_robot(self, vx: float, vy: float, vyaw: float) -> None: ... - def rotate_head(self, pitch: float, yaw: float) -> None: ... - def wave_hand(self, action: HandAction) -> None: ... + """High-level locomotion and body-control client for the robot.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create a client. + + Args: + startup_wait_sec: Optional one-time wait before the first RPC call. + ``None`` uses SDK default startup wait. + """ + ... + + def change_mode(self, mode: RobotMode) -> None: + """Request robot mode transition.""" + ... + + def get_mode(self) -> GetModeResponse: + """Fetch current robot mode.""" + ... + + def get_status(self) -> GetStatusResponse: + """Fetch current robot status summary.""" + ... + + def get_robot_info(self) -> GetRobotInfoResponse: + """Fetch robot identity/version metadata.""" + ... + + def move_robot(self, vx: float, vy: float, vyaw: float) -> None: + """Command base motion in body frame.""" + ... + + def rotate_head(self, pitch: float, yaw: float) -> None: + """Rotate head to target pitch/yaw angles.""" + ... + + def wave_hand(self, action: HandAction) -> None: + """Trigger hand wave/open-close style action.""" + ... + def rotate_head_with_direction( self, pitch_direction: int, yaw_direction: int - ) -> None: ... - def lie_down(self) -> None: ... - def get_up(self) -> None: ... - def get_up_with_mode(self, mode: RobotMode) -> None: ... - def shoot(self) -> None: ... - def push_up(self) -> None: ... + ) -> None: + """Rotate head using directional step commands.""" + ... + + def lie_down(self) -> None: + """Command robot to lie down.""" + ... + + def get_up(self) -> None: + """Command robot to stand up.""" + ... + + def get_up_with_mode(self, mode: RobotMode) -> None: + """Stand up and transition into specified mode.""" + ... + + def shoot(self) -> None: + """Trigger shoot action.""" + ... + + def push_up(self) -> None: + """Trigger push-up action.""" + ... + def move_hand_end_effector( self, target_posture: Posture, time_millis: int, hand_index: Hand, - ) -> None: ... + ) -> None: + """Move a hand end effector to target posture.""" + ... + def move_hand_end_effector_with_aux( self, target_posture: Posture, aux_posture: Posture, time_millis: int, hand_index: Hand, - ) -> None: ... + ) -> None: + """Move end effector with auxiliary posture constraint.""" + ... + def move_hand_end_effector_v2( self, target_posture: Posture, time_millis: int, hand_index: Hand, - ) -> None: ... - def stop_hand_end_effector(self) -> None: ... + ) -> None: + """Move end effector using v2 behavior flag.""" + ... + + def stop_hand_end_effector(self) -> None: + """Stop active hand end-effector motion.""" + ... + def control_gripper( self, motion_param: GripperMotionParameter, mode: GripperControlMode, hand_index: Hand, - ) -> None: ... - def get_frame_transform(self, src: Frame, dst: Frame) -> Transform: ... - def switch_hand_end_effector_control_mode(self, switch_on: bool) -> None: ... - def handshake(self, action: HandAction) -> None: ... + ) -> None: + """Control gripper position/force.""" + ... + + def get_frame_transform(self, src: Frame, dst: Frame) -> Transform: + """Query transform between two robot frames.""" + ... + + def switch_hand_end_effector_control_mode(self, switch_on: bool) -> None: + """Enable or disable hand end-effector control mode.""" + ... + + def handshake(self, action: HandAction) -> None: + """Trigger handshake action variant.""" + ... + def control_dexterous_hand( self, finger_params: list[DexterousFingerParameter], hand_index: Hand, hand_type: BoosterHandType, - ) -> None: ... + ) -> None: + """Send low-level dexterous-hand finger commands.""" + ... + def control_dexterous_hand_default( self, finger_params: list[DexterousFingerParameter], hand_index: Hand, - ) -> None: ... - def dance(self, dance_id: DanceId) -> None: ... - def play_sound(self, sound_file_path: str) -> None: ... - def stop_sound(self) -> None: ... - def zero_torque_drag(self, active: bool) -> None: ... - def record_trajectory(self, active: bool) -> None: ... - def replay_trajectory(self, traj_file_path: str) -> None: ... - def whole_body_dance(self, dance_id: WholeBodyDanceId) -> None: ... - def upper_body_custom_control(self, start: bool) -> None: ... - def reset_odometry(self) -> None: ... + ) -> None: + """Control dexterous hand using default hand type.""" + ... + + def dance(self, dance_id: DanceId) -> None: + """Start predefined dance gesture.""" + ... + + def play_sound(self, sound_file_path: str) -> None: + """Play a sound file on robot audio output.""" + ... + + def stop_sound(self) -> None: + """Stop currently playing sound.""" + ... + + def zero_torque_drag(self, active: bool) -> None: + """Enable/disable zero-torque drag mode.""" + ... + + def record_trajectory(self, active: bool) -> None: + """Start or stop trajectory recording.""" + ... + + def replay_trajectory(self, traj_file_path: str) -> None: + """Replay a recorded trajectory from path.""" + ... + + def whole_body_dance(self, dance_id: WholeBodyDanceId) -> None: + """Start whole-body dance routine.""" + ... + + def upper_body_custom_control(self, start: bool) -> None: + """Toggle upper-body custom control mode.""" + ... + + def reset_odometry(self) -> None: + """Reset base odometry estimate.""" + ... + def load_custom_trained_traj( self, traj: CustomTrainedTraj, - ) -> LoadCustomTrainedTrajResponse: ... - def activate_custom_trained_traj(self, tid: str) -> None: ... - def unload_custom_trained_traj(self, tid: str) -> None: ... - def enter_wbc_gait(self) -> None: ... - def exit_wbc_gait(self) -> None: ... - def publish_gripper_command(self, command: GripperCommand) -> None: ... + ) -> LoadCustomTrainedTrajResponse: + """Load a custom trained trajectory and return its id.""" + ... + + def activate_custom_trained_traj(self, tid: str) -> None: + """Activate previously loaded custom trajectory by id.""" + ... + + def unload_custom_trained_traj(self, tid: str) -> None: + """Unload previously loaded custom trajectory by id.""" + ... + + def enter_wbc_gait(self) -> None: + """Enter WBC gait mode.""" + ... + + def exit_wbc_gait(self) -> None: + """Exit WBC gait mode.""" + ... + + def publish_gripper_command(self, command: GripperCommand) -> None: + """Publish low-level gripper command message.""" + ... + def publish_gripper( self, hand: Hand, mode: GripperMode, motion_param: int, speed: int | None = ..., - ) -> None: ... + ) -> None: + """Convenience wrapper for publishing gripper command fields.""" + ... class AiClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... - def start_ai_chat(self, param: StartAiChatParameter) -> None: ... - def stop_ai_chat(self) -> None: ... - def speak(self, param: SpeakParameter) -> None: ... - def start_face_tracking(self) -> None: ... - def stop_face_tracking(self) -> None: ... + """Client for AI chat and speech features.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create AI client. + + Args: + startup_wait_sec: Optional one-time wait before first RPC call. + """ + ... + + def start_ai_chat(self, param: StartAiChatParameter) -> None: + """Start AI chat session with provided config.""" + ... + + def stop_ai_chat(self) -> None: + """Stop active AI chat session.""" + ... + + def speak(self, param: SpeakParameter) -> None: + """Send message for AI speech output.""" + ... + + def start_face_tracking(self) -> None: + """Enable AI face tracking mode.""" + ... + + def stop_face_tracking(self) -> None: + """Disable AI face tracking mode.""" + ... class LuiClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... - def start_asr(self) -> None: ... - def stop_asr(self) -> None: ... - def start_tts(self, config: LuiTtsConfig) -> None: ... - def stop_tts(self) -> None: ... - def send_tts_text(self, param: LuiTtsParameter) -> None: ... + """Client for LUI ASR/TTS APIs.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create LUI client. + + Args: + startup_wait_sec: Optional one-time wait before first RPC call. + """ + ... + + def start_asr(self) -> None: + """Start ASR stream.""" + ... + + def stop_asr(self) -> None: + """Stop ASR stream.""" + ... + + def start_tts(self, config: LuiTtsConfig) -> None: + """Start TTS engine with given configuration.""" + ... + + def stop_tts(self) -> None: + """Stop TTS engine.""" + ... + + def send_tts_text(self, param: LuiTtsParameter) -> None: + """Send text payload for TTS synthesis.""" + ... class LightControlClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... - def set_led_light_color(self, r: int, g: int, b: int) -> None: ... - def stop_led_light_control(self) -> None: ... + """Client for LED light control APIs.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create light-control client. + + Args: + startup_wait_sec: Optional one-time wait before first RPC call. + """ + ... + + def set_led_light_color(self, r: int, g: int, b: int) -> None: + """Set LED strip color using RGB values (0-255).""" + ... + + def stop_led_light_control(self) -> None: + """Stop active LED control program/effect.""" + ... class VisionClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... + """Client for vision inference APIs.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create vision client. + + Args: + startup_wait_sec: Optional one-time wait before first RPC call. + """ + ... + def start_vision_service( self, enable_position: bool, enable_color: bool, enable_face_detection: bool, - ) -> None: ... - def stop_vision_service(self) -> None: ... + ) -> None: + """Start vision service with selected feature flags.""" + ... + + def stop_vision_service(self) -> None: + """Stop vision service.""" + ... + def get_detection_object_with_ratio( self, focus_ratio: float - ) -> list[DetectResults]: ... - def get_detection_object(self) -> list[DetectResults]: ... + ) -> list[DetectResults]: + """Get detected objects using custom focus ratio.""" + ... + + def get_detection_object(self) -> list[DetectResults]: + """Get detected objects using default focus ratio.""" + ... class X5CameraClient: - def __init__(self, startup_wait_sec: float | None = ...) -> None: ... - def change_mode(self, mode: CameraSetMode) -> None: ... - def get_status(self) -> X5CameraGetStatusResponse: ... + """Client for X5 camera control and status APIs.""" + + def __init__(self, startup_wait_sec: float | None = ...) -> None: + """Create X5 camera client. + + Args: + startup_wait_sec: Optional one-time wait before first RPC call. + """ + ... + + def change_mode(self, mode: CameraSetMode) -> None: + """Change camera mode.""" + ... + + def get_status(self) -> X5CameraGetStatusResponse: + """Get current camera status.""" + ... From a5a94546c166b29747825530ca62e65556a2f068 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 23:20:42 +0100 Subject: [PATCH 11/13] Consistent import scheme --- README.md | 3 +- booster_sdk_py/booster_sdk/__init__.py | 3 +- booster_sdk_py/booster_sdk/client/ai.py | 18 +++- booster_sdk_py/booster_sdk/client/booster.py | 60 ++++++++++++- .../booster_sdk/client/light_control.py | 3 +- booster_sdk_py/booster_sdk/client/lui.py | 10 ++- booster_sdk_py/booster_sdk/client/vision.py | 4 +- .../booster_sdk/client/x5_camera.py | 12 ++- booster_sdk_py/booster_sdk/types.py | 89 ------------------- 9 files changed, 103 insertions(+), 99 deletions(-) delete mode 100644 booster_sdk_py/booster_sdk/types.py diff --git a/README.md b/README.md index 8ab8bdf..202fb87 100644 --- a/README.md +++ b/README.md @@ -57,8 +57,7 @@ pip install booster-sdk Note: Python bindings are experimental. ```python -from booster_sdk.client.booster import BoosterClient -from booster_sdk.types import GripperCommand, Hand, RobotMode +from booster_sdk.client.booster import BoosterClient, GripperCommand, Hand, RobotMode client = BoosterClient() diff --git a/booster_sdk_py/booster_sdk/__init__.py b/booster_sdk_py/booster_sdk/__init__.py index 84ca893..4b0788d 100644 --- a/booster_sdk_py/booster_sdk/__init__.py +++ b/booster_sdk_py/booster_sdk/__init__.py @@ -2,9 +2,8 @@ Use module-scoped imports: - `booster_sdk.client.` -- `booster_sdk.types` """ from __future__ import annotations -__all__ = ["client", "types"] +__all__ = ["client"] diff --git a/booster_sdk_py/booster_sdk/client/ai.py b/booster_sdk_py/booster_sdk/client/ai.py index 56ccd12..23da190 100644 --- a/booster_sdk_py/booster_sdk/client/ai.py +++ b/booster_sdk_py/booster_sdk/client/ai.py @@ -5,5 +5,21 @@ import booster_sdk_bindings as bindings AiClient = bindings.AiClient +BoosterSdkError = bindings.BoosterSdkError +BOOSTER_ROBOT_USER_ID = bindings.BOOSTER_ROBOT_USER_ID +TtsConfig = bindings.TtsConfig +LlmConfig = bindings.LlmConfig +AsrConfig = bindings.AsrConfig +StartAiChatParameter = bindings.StartAiChatParameter +SpeakParameter = bindings.SpeakParameter -__all__ = ["AiClient"] +__all__ = [ + "AiClient", + "BoosterSdkError", + "BOOSTER_ROBOT_USER_ID", + "TtsConfig", + "LlmConfig", + "AsrConfig", + "StartAiChatParameter", + "SpeakParameter", +] diff --git a/booster_sdk_py/booster_sdk/client/booster.py b/booster_sdk_py/booster_sdk/client/booster.py index 7080c63..4a5df12 100644 --- a/booster_sdk_py/booster_sdk/client/booster.py +++ b/booster_sdk_py/booster_sdk/client/booster.py @@ -5,5 +5,63 @@ import booster_sdk_bindings as bindings BoosterClient = bindings.BoosterClient +BoosterSdkError = bindings.BoosterSdkError +RobotMode = bindings.RobotMode +Hand = bindings.Hand +GripperMode = bindings.GripperMode +GripperCommand = bindings.GripperCommand +HandAction = bindings.HandAction +Frame = bindings.Frame +GripperControlMode = bindings.GripperControlMode +BoosterHandType = bindings.BoosterHandType +DanceId = bindings.DanceId +WholeBodyDanceId = bindings.WholeBodyDanceId +JointOrder = bindings.JointOrder +BodyControl = bindings.BodyControl +Action = bindings.Action +Position = bindings.Position +Orientation = bindings.Orientation +Posture = bindings.Posture +Quaternion = bindings.Quaternion +Transform = bindings.Transform +GripperMotionParameter = bindings.GripperMotionParameter +DexterousFingerParameter = bindings.DexterousFingerParameter +CustomModelParams = bindings.CustomModelParams +CustomModel = bindings.CustomModel +CustomTrainedTraj = bindings.CustomTrainedTraj +GetModeResponse = bindings.GetModeResponse +GetStatusResponse = bindings.GetStatusResponse +GetRobotInfoResponse = bindings.GetRobotInfoResponse +LoadCustomTrainedTrajResponse = bindings.LoadCustomTrainedTrajResponse -__all__ = ["BoosterClient"] +__all__ = [ + "BoosterClient", + "BoosterSdkError", + "RobotMode", + "Hand", + "GripperMode", + "GripperCommand", + "HandAction", + "Frame", + "GripperControlMode", + "BoosterHandType", + "DanceId", + "WholeBodyDanceId", + "JointOrder", + "BodyControl", + "Action", + "Position", + "Orientation", + "Posture", + "Quaternion", + "Transform", + "GripperMotionParameter", + "DexterousFingerParameter", + "CustomModelParams", + "CustomModel", + "CustomTrainedTraj", + "GetModeResponse", + "GetStatusResponse", + "GetRobotInfoResponse", + "LoadCustomTrainedTrajResponse", +] diff --git a/booster_sdk_py/booster_sdk/client/light_control.py b/booster_sdk_py/booster_sdk/client/light_control.py index 3f06aa7..4987ef7 100644 --- a/booster_sdk_py/booster_sdk/client/light_control.py +++ b/booster_sdk_py/booster_sdk/client/light_control.py @@ -5,5 +5,6 @@ import booster_sdk_bindings as bindings LightControlClient = bindings.LightControlClient +BoosterSdkError = bindings.BoosterSdkError -__all__ = ["LightControlClient"] +__all__ = ["LightControlClient", "BoosterSdkError"] diff --git a/booster_sdk_py/booster_sdk/client/lui.py b/booster_sdk_py/booster_sdk/client/lui.py index e3caf59..2d0125e 100644 --- a/booster_sdk_py/booster_sdk/client/lui.py +++ b/booster_sdk_py/booster_sdk/client/lui.py @@ -5,5 +5,13 @@ import booster_sdk_bindings as bindings LuiClient = bindings.LuiClient +BoosterSdkError = bindings.BoosterSdkError +LuiTtsConfig = bindings.LuiTtsConfig +LuiTtsParameter = bindings.LuiTtsParameter -__all__ = ["LuiClient"] +__all__ = [ + "LuiClient", + "BoosterSdkError", + "LuiTtsConfig", + "LuiTtsParameter", +] diff --git a/booster_sdk_py/booster_sdk/client/vision.py b/booster_sdk_py/booster_sdk/client/vision.py index 8830150..a52a4d8 100644 --- a/booster_sdk_py/booster_sdk/client/vision.py +++ b/booster_sdk_py/booster_sdk/client/vision.py @@ -5,5 +5,7 @@ import booster_sdk_bindings as bindings VisionClient = bindings.VisionClient +BoosterSdkError = bindings.BoosterSdkError +DetectResults = bindings.DetectResults -__all__ = ["VisionClient"] +__all__ = ["VisionClient", "BoosterSdkError", "DetectResults"] diff --git a/booster_sdk_py/booster_sdk/client/x5_camera.py b/booster_sdk_py/booster_sdk/client/x5_camera.py index 463f7e2..7495090 100644 --- a/booster_sdk_py/booster_sdk/client/x5_camera.py +++ b/booster_sdk_py/booster_sdk/client/x5_camera.py @@ -5,5 +5,15 @@ import booster_sdk_bindings as bindings X5CameraClient = bindings.X5CameraClient +BoosterSdkError = bindings.BoosterSdkError +CameraSetMode = bindings.CameraSetMode +CameraControlStatus = bindings.CameraControlStatus +X5CameraGetStatusResponse = bindings.X5CameraGetStatusResponse -__all__ = ["X5CameraClient"] +__all__ = [ + "X5CameraClient", + "BoosterSdkError", + "CameraSetMode", + "CameraControlStatus", + "X5CameraGetStatusResponse", +] diff --git a/booster_sdk_py/booster_sdk/types.py b/booster_sdk_py/booster_sdk/types.py deleted file mode 100644 index d8fea7f..0000000 --- a/booster_sdk_py/booster_sdk/types.py +++ /dev/null @@ -1,89 +0,0 @@ -"""Type definitions for the Booster SDK bindings.""" - -from __future__ import annotations - -from booster_sdk_bindings import ( - BOOSTER_ROBOT_USER_ID, - Action, - AsrConfig, - BoosterHandType, - BoosterSdkError, - BodyControl, - CameraControlStatus, - CameraSetMode, - CustomModel, - CustomModelParams, - CustomTrainedTraj, - DanceId, - DetectResults, - DexterousFingerParameter, - Frame, - GetModeResponse, - GetRobotInfoResponse, - GetStatusResponse, - GripperCommand, - GripperControlMode, - GripperMode, - GripperMotionParameter, - Hand, - HandAction, - JointOrder, - LlmConfig, - LoadCustomTrainedTrajResponse, - LuiTtsConfig, - LuiTtsParameter, - Orientation, - Position, - Posture, - Quaternion, - RobotMode, - SpeakParameter, - StartAiChatParameter, - Transform, - TtsConfig, - WholeBodyDanceId, - X5CameraGetStatusResponse, -) - -__all__ = [ - "BOOSTER_ROBOT_USER_ID", - "BoosterSdkError", - "RobotMode", - "Hand", - "GripperMode", - "GripperCommand", - "HandAction", - "Frame", - "GripperControlMode", - "BoosterHandType", - "DanceId", - "WholeBodyDanceId", - "JointOrder", - "BodyControl", - "Action", - "CameraSetMode", - "CameraControlStatus", - "Position", - "Orientation", - "Posture", - "Quaternion", - "Transform", - "GripperMotionParameter", - "DexterousFingerParameter", - "CustomModelParams", - "CustomModel", - "CustomTrainedTraj", - "TtsConfig", - "LlmConfig", - "AsrConfig", - "StartAiChatParameter", - "SpeakParameter", - "LuiTtsConfig", - "LuiTtsParameter", - "GetModeResponse", - "GetStatusResponse", - "GetRobotInfoResponse", - "LoadCustomTrainedTrajResponse", - "X5CameraGetStatusResponse", - "DetectResults", -] From f1064687ad17cc73e6f8bd7cde771b31bcc319b4 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 23:39:56 +0100 Subject: [PATCH 12/13] clean up docs --- README.md | 2 -- booster_sdk_py/booster_sdk/__init__.py | 6 +----- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/README.md b/README.md index 202fb87..c457c69 100644 --- a/README.md +++ b/README.md @@ -54,8 +54,6 @@ pip install booster-sdk ### Python API Example -Note: Python bindings are experimental. - ```python from booster_sdk.client.booster import BoosterClient, GripperCommand, Hand, RobotMode diff --git a/booster_sdk_py/booster_sdk/__init__.py b/booster_sdk_py/booster_sdk/__init__.py index 4b0788d..8cc3b78 100644 --- a/booster_sdk_py/booster_sdk/__init__.py +++ b/booster_sdk_py/booster_sdk/__init__.py @@ -1,8 +1,4 @@ -"""Booster SDK Python package. - -Use module-scoped imports: -- `booster_sdk.client.` -""" +"""Booster SDK Python package.""" from __future__ import annotations From 5abee13d4be2d8e46bd94ee1dc2191fcfc8098a3 Mon Sep 17 00:00:00 2001 From: Gijs de Jong Date: Thu, 26 Feb 2026 23:40:38 +0100 Subject: [PATCH 13/13] 0.1.0-alpha.10 --- Cargo.lock | 4 ++-- Cargo.toml | 2 +- pixi.toml | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index d711e5f..50a6db2 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -46,7 +46,7 @@ checksum = "812e12b5285cc515a9c72a5c1d3b6d46a19dac5acfef5265968c166106e31dd3" [[package]] name = "booster_sdk" -version = "0.1.0-alpha.9" +version = "0.1.0-alpha.10" dependencies = [ "rustdds", "serde", @@ -61,7 +61,7 @@ dependencies = [ [[package]] name = "booster_sdk_py" -version = "0.1.0-alpha.9" +version = "0.1.0-alpha.10" dependencies = [ "booster_sdk", "pyo3", diff --git a/Cargo.toml b/Cargo.toml index f595515..2ed992f 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -3,7 +3,7 @@ members = ["booster_sdk", "booster_sdk_py"] resolver = "2" [workspace.package] -version = "0.1.0-alpha.9" +version = "0.1.0-alpha.10" edition = "2024" authors = ["Team whIRLwind"] license = "MIT OR Apache-2.0" diff --git a/pixi.toml b/pixi.toml index ee40ce5..937cee7 100644 --- a/pixi.toml +++ b/pixi.toml @@ -3,7 +3,7 @@ authors = ["Team whIRLwind"] channels = ["conda-forge"] name = "booster-sdk" platforms = ["osx-arm64", "linux-64", "linux-aarch64"] -version = "0.1.0-alpha.9" +version = "0.1.0-alpha.10" [environments] py = ["wheel-build", "python-tasks"]