arci_ros/ros_control/
traits.rs1use std::sync::{Arc, LazyLock};
2
3use arci::JointTrajectoryClient;
4use auto_impl::auto_impl;
5
6use crate::JointTrajectoryClientWrapperConfig;
7
8pub trait JointStateProvider {
9 fn get_joint_state(&self) -> Result<(Vec<String>, Vec<f64>), arci::Error>;
10}
11
12#[auto_impl(&)]
13pub trait RosControlClientBuilder {
14 fn build_joint_state_provider(
15 &self,
16 joint_state_topic_name: impl Into<String>,
17 ) -> Arc<LazyJointStateProvider>;
18 fn build_joint_trajectory_client(
19 &self,
20 lazy: bool,
21 joint_state_provider: Arc<LazyJointStateProvider>,
22 ) -> Result<Arc<dyn JointTrajectoryClient>, arci::Error>;
23 fn state_topic(&self) -> String;
24 fn wrapper_config(&self) -> &JointTrajectoryClientWrapperConfig;
25 fn name(&self) -> &str;
26}
27
28pub(crate) type LazyJointStateProvider = LazyLock<
29 Box<dyn JointStateProvider + Send + Sync>,
30 Box<dyn FnOnce() -> Box<dyn JointStateProvider + Send + Sync> + Send + Sync>,
31>;