openrr_teleop/
joints_pose_sender.rs

1use std::{collections::HashMap, time::Duration};
2
3use arci::{
4    gamepad::{Button, GamepadEvent},
5    JointTrajectoryClient, Speaker,
6};
7use async_trait::async_trait;
8use openrr_client::JointsPose;
9use parking_lot::Mutex;
10use schemars::JsonSchema;
11use serde::{Deserialize, Serialize};
12
13use crate::ControlMode;
14
15struct JointsPoseSenderInner {
16    joints_poses: Vec<JointsPose>,
17    submode: String,
18    pose_index: usize,
19    is_trigger_holding: bool,
20    is_sending: bool,
21}
22
23impl JointsPoseSenderInner {
24    fn new(joints_poses: Vec<JointsPose>) -> Self {
25        Self {
26            submode: format!(
27                " {} {}",
28                joints_poses[0].client_name, joints_poses[0].pose_name
29            ),
30            joints_poses,
31            pose_index: 0,
32            is_trigger_holding: false,
33            is_sending: false,
34        }
35    }
36
37    fn handle_event(&mut self, event: arci::gamepad::GamepadEvent) -> Option<&str> {
38        match event {
39            GamepadEvent::ButtonPressed(Button::East) => {
40                self.pose_index = (self.pose_index + 1) % self.joints_poses.len();
41                let joints_pose = &self.joints_poses[self.pose_index];
42                self.submode = format!(" {} {}", joints_pose.client_name, joints_pose.pose_name);
43                return Some(&self.submode);
44            }
45            GamepadEvent::ButtonPressed(Button::RightTrigger2) => {
46                self.is_trigger_holding = true;
47            }
48            GamepadEvent::ButtonReleased(Button::RightTrigger2) => {
49                self.is_trigger_holding = false;
50                self.is_sending = false;
51            }
52            GamepadEvent::ButtonPressed(Button::West) => {
53                self.is_sending = true;
54            }
55            GamepadEvent::ButtonReleased(Button::West) => {
56                self.is_sending = false;
57            }
58            GamepadEvent::Disconnected => {
59                self.is_trigger_holding = false;
60                self.is_sending = false;
61            }
62            _ => {}
63        }
64        None
65    }
66
67    fn get_target_name_positions(&self) -> (String, Vec<f64>) {
68        let joints_pose = &self.joints_poses[self.pose_index];
69        (
70            joints_pose.client_name.to_owned(),
71            joints_pose.positions.to_owned(),
72        )
73    }
74}
75pub struct JointsPoseSender<S, J>
76where
77    S: Speaker,
78    J: JointTrajectoryClient,
79{
80    mode: String,
81    joint_trajectory_clients: HashMap<String, J>,
82    speaker: S,
83    duration: Duration,
84    inner: Mutex<JointsPoseSenderInner>,
85}
86
87impl<S, J> JointsPoseSender<S, J>
88where
89    S: Speaker,
90    J: JointTrajectoryClient,
91{
92    pub fn new(
93        mode: String,
94        joints_poses: Vec<JointsPose>,
95        joint_trajectory_clients: HashMap<String, J>,
96        speaker: S,
97        duration: Duration,
98    ) -> Self {
99        Self {
100            mode,
101            joint_trajectory_clients,
102            speaker,
103            duration,
104            inner: Mutex::new(JointsPoseSenderInner::new(joints_poses)),
105        }
106    }
107
108    pub fn new_from_config(
109        config: JointsPoseSenderConfig,
110        joints_poses: Vec<JointsPose>,
111        joint_trajectory_clients: HashMap<String, J>,
112        speaker: S,
113    ) -> Self {
114        Self::new(
115            config.mode,
116            joints_poses,
117            joint_trajectory_clients,
118            speaker,
119            Duration::from_secs_f64(config.duration_secs),
120        )
121    }
122}
123
124#[async_trait]
125impl<S, J> ControlMode for JointsPoseSender<S, J>
126where
127    S: Speaker,
128    J: JointTrajectoryClient,
129{
130    fn handle_event(&self, event: arci::gamepad::GamepadEvent) {
131        if let Some(submode) = self.inner.lock().handle_event(event) {
132            // do not wait
133            drop(
134                self.speaker
135                    .speak(&format!("{}{submode}", self.mode))
136                    .unwrap(),
137            );
138        }
139    }
140
141    async fn proc(&self) {
142        let inner = self.inner.lock();
143        let (name, target) = inner.get_target_name_positions();
144        let client = self.joint_trajectory_clients.get(&name).unwrap();
145        drop(
146            client
147                .send_joint_positions(
148                    if inner.is_sending && inner.is_trigger_holding {
149                        target
150                    } else {
151                        client.current_joint_positions().unwrap()
152                    },
153                    self.duration,
154                )
155                .unwrap(),
156        );
157    }
158
159    fn mode(&self) -> &str {
160        &self.mode
161    }
162
163    fn submode(&self) -> String {
164        self.inner.lock().submode.to_owned()
165    }
166}
167
168#[derive(Debug, Serialize, Deserialize, Clone, JsonSchema)]
169#[serde(deny_unknown_fields)]
170pub struct JointsPoseSenderConfig {
171    #[serde(default = "default_mode")]
172    pub mode: String,
173    #[serde(default = "default_duration_secs")]
174    pub duration_secs: f64,
175}
176
177fn default_mode() -> String {
178    "pose".to_string()
179}
180
181fn default_duration_secs() -> f64 {
182    2.0
183}
184
185#[cfg(test)]
186mod test {
187    use arci::DummyJointTrajectoryClient;
188    use assert_approx_eq::*;
189    use openrr_client::PrintSpeaker;
190
191    use super::*;
192
193    #[test]
194    fn test_joints_pose_sender_inner() {
195        let joints_poses = vec![
196            JointsPose {
197                pose_name: String::from("pose0"),
198                client_name: String::from("client0"),
199                positions: vec![1.2, 3.4, 5.6],
200            },
201            JointsPose {
202                pose_name: String::from("pose1"),
203                client_name: String::from("client1"),
204                positions: vec![7.8, 9.1, 2.3],
205            },
206        ];
207        let mut inner = JointsPoseSenderInner::new(joints_poses);
208
209        assert_eq!(inner.get_target_name_positions().0, String::from("client0"));
210        assert_approx_eq!(inner.get_target_name_positions().1[0], 1.2f64);
211        assert_approx_eq!(inner.get_target_name_positions().1[1], 3.4f64);
212        assert_approx_eq!(inner.get_target_name_positions().1[2], 5.6f64);
213
214        // Change submode
215        inner.handle_event(GamepadEvent::ButtonPressed(Button::East));
216        assert_eq!(inner.submode, String::from(" client1 pose1"));
217        assert_eq!(inner.pose_index, 1);
218
219        // Case that enable switch is on
220        inner.handle_event(GamepadEvent::ButtonPressed(Button::RightTrigger2));
221        assert!(inner.is_trigger_holding);
222        assert!(!inner.is_sending);
223
224        // Case that enable switch becomes off
225        inner.handle_event(GamepadEvent::ButtonReleased(Button::RightTrigger2));
226        assert!(!inner.is_trigger_holding);
227        assert!(!inner.is_sending);
228
229        // Send pose
230        inner.handle_event(GamepadEvent::ButtonPressed(Button::West));
231        assert!(inner.is_sending);
232
233        // Stop send command
234        inner.handle_event(GamepadEvent::ButtonReleased(Button::West));
235        assert!(!inner.is_sending);
236
237        // Disconnected
238        inner.handle_event(GamepadEvent::Disconnected);
239        assert!(!inner.is_trigger_holding);
240        assert!(!inner.is_sending);
241    }
242
243    #[test]
244    fn test_joints_pose_sender() {
245        let mode = String::from("test_mode");
246        let joints_poses = vec![JointsPose {
247            pose_name: String::from("pose0"),
248            client_name: String::from("client0"),
249            positions: vec![1.2, 3.4, 5.6],
250        }];
251        let joint_names = vec![String::from("test_joint1")];
252        let joint_trajectory_clients = HashMap::from([(
253            String::from("client0"),
254            DummyJointTrajectoryClient::new(joint_names.clone()),
255        )]);
256        let speaker = PrintSpeaker::new();
257        let duration = Duration::from_millis(5);
258
259        let inner = Mutex::new(JointsPoseSenderInner::new(joints_poses.clone()));
260
261        let joints_pose_sender = JointsPoseSender::new(
262            mode.clone(),
263            joints_poses,
264            joint_trajectory_clients,
265            speaker,
266            duration,
267        );
268
269        // Test for generate joints_pose_sender
270        assert_eq!(joints_pose_sender.mode, mode);
271        assert_eq!(
272            format!("{:?}", DummyJointTrajectoryClient::new(joint_names)),
273            format!(
274                "{:?}",
275                joints_pose_sender.joint_trajectory_clients["client0"]
276            )
277        );
278        assert!(duration.eq(&joints_pose_sender.duration));
279        assert_eq!(
280            format!("{:?}", joints_pose_sender.inner.lock().joints_poses),
281            format!("{:?}", inner.lock().joints_poses)
282        );
283
284        // Test fot getting mode of joints_pose_sender
285        let joints_pose_sender_mode = joints_pose_sender.mode();
286        assert_eq!(joints_pose_sender_mode, mode);
287        let submode = joints_pose_sender.submode();
288        assert_eq!(joints_pose_sender.inner.lock().submode, submode);
289    }
290
291    #[tokio::test]
292    async fn test_joints_pose_sender_proc() {
293        let joints_poses = vec![JointsPose {
294            pose_name: String::from("pose0"),
295            client_name: String::from("client0"),
296            positions: vec![1.2, 3.4, 5.6],
297        }];
298        let joint_names = vec![
299            String::from("joint1"),
300            String::from("joint2"),
301            String::from("joint3"),
302        ];
303
304        let joints_pose_sender = JointsPoseSender {
305            mode: String::from("test_mode"),
306            joint_trajectory_clients: HashMap::from([(
307                String::from("client0"),
308                DummyJointTrajectoryClient::new(joint_names.clone()),
309            )]),
310            speaker: PrintSpeaker::new(),
311            duration: Duration::from_millis(5),
312            inner: Mutex::new(JointsPoseSenderInner {
313                joints_poses: joints_poses.clone(),
314                submode: String::from("submode"),
315                pose_index: 0,
316                is_trigger_holding: false,
317                is_sending: false,
318            }),
319        };
320        joints_pose_sender.proc().await;
321
322        let current_state = joints_pose_trajectory_client_current_state(&joints_pose_sender);
323
324        assert_approx_eq!(current_state[0], 0.0);
325        assert_approx_eq!(current_state[1], 0.0);
326        assert_approx_eq!(current_state[2], 0.0);
327
328        let joints_pose_sender = JointsPoseSender {
329            mode: String::from("test_mode"),
330            joint_trajectory_clients: HashMap::from([(
331                String::from("client0"),
332                DummyJointTrajectoryClient::new(joint_names.clone()),
333            )]),
334            speaker: PrintSpeaker::new(),
335            duration: Duration::from_millis(5),
336            inner: Mutex::new(JointsPoseSenderInner {
337                joints_poses: joints_poses.clone(),
338                submode: String::from("submode"),
339                pose_index: 0,
340                is_trigger_holding: true,
341                is_sending: true,
342            }),
343        };
344        joints_pose_sender.proc().await;
345
346        let current_state = joints_pose_trajectory_client_current_state(&joints_pose_sender);
347
348        assert_approx_eq!(current_state[0], 1.2);
349        assert_approx_eq!(current_state[1], 3.4);
350        assert_approx_eq!(current_state[2], 5.6);
351    }
352
353    fn joints_pose_trajectory_client_current_state(
354        joints_pose_sender: &JointsPoseSender<PrintSpeaker, DummyJointTrajectoryClient>,
355    ) -> Vec<f64> {
356        let inner = joints_pose_sender.inner.lock();
357        let (name, target) = inner.get_target_name_positions();
358
359        let client = joints_pose_sender
360            .joint_trajectory_clients
361            .get(&name)
362            .unwrap();
363        drop(
364            client
365                .send_joint_positions(
366                    if inner.is_sending && inner.is_trigger_holding {
367                        target
368                    } else {
369                        client.current_joint_positions().unwrap()
370                    },
371                    joints_pose_sender.duration,
372                )
373                .unwrap(),
374        );
375
376        joints_pose_sender.joint_trajectory_clients[&name]
377            .current_joint_positions()
378            .unwrap()
379    }
380
381    #[test]
382    fn test_default_mode() {
383        assert_eq!(default_mode(), "pose".to_string());
384    }
385
386    #[test]
387    fn test_default_duration_secs() {
388        let def = default_duration_secs();
389        assert_approx_eq!(def, 2.0f64);
390    }
391}