1use std::{
2 error::Error,
3 fs::File,
4 io::{BufRead, BufReader},
5 path::PathBuf,
6 process::Command,
7 thread::sleep,
8 time::{Duration, Instant},
9};
10
11use arci::{BaseVelocity, Localization, MoveBase, Navigation};
12use async_recursion::async_recursion;
13use clap::Parser;
14use clap_complete::Shell;
15use k::nalgebra::{Isometry2, Vector2};
16use openrr_client::{isometry, RobotClient};
17use rustyline::{error::ReadlineError, DefaultEditor};
18use tracing::{error, info};
19
20use crate::Error as OpenrrCommandError;
21
22fn parse_joints<T, U>(s: &str) -> Result<(T, U), Box<dyn Error + Send + Sync>>
23where
24 T: std::str::FromStr,
25 T::Err: Error + Send + Sync + 'static,
26 U: std::str::FromStr,
27 U::Err: Error + Send + Sync + 'static,
28{
29 let pos = s
30 .find('=')
31 .ok_or_else(|| format!("invalid KEY=value: no `=` found in `{s}`"))?;
32 Ok((s[..pos].parse()?, s[pos + 1..].parse()?))
33}
34
35#[derive(Parser, Debug)]
36#[clap(rename_all = "snake_case")]
37pub enum RobotCommand {
38 SendJoints {
40 name: String,
41 #[clap(short, long, default_value = "3.0")]
42 duration: f64,
43 #[clap(name = "interpolate", short, long)]
46 use_interpolation: bool,
47 #[clap(short, value_parser = parse_joints::<usize, f64>, long)]
51 joint: Vec<(usize, f64)>,
52 #[clap(long, default_value = "0.05")]
53 max_resolution_for_interpolation: f64,
54 #[clap(long, default_value = "10")]
55 min_number_of_points_for_interpolation: i32,
56 },
57 SendJointsPose {
59 name: String,
60 pose_name: String,
61 #[clap(short, long, default_value = "3.0")]
62 duration: f64,
63 },
64 MoveIk {
66 name: String,
67 #[clap(short, long)]
68 x: Option<f64>,
69 #[clap(short, long)]
70 y: Option<f64>,
71 #[clap(short, long)]
72 z: Option<f64>,
73 #[clap(long)]
74 yaw: Option<f64>,
75 #[clap(short, long)]
76 pitch: Option<f64>,
77 #[clap(short, long)]
78 roll: Option<f64>,
79 #[clap(short, long, default_value = "3.0")]
80 duration: f64,
81 #[clap(name = "interpolate", short, long)]
83 use_interpolation: bool,
84 #[clap(name = "local", short, long)]
85 is_local: bool,
86 #[clap(long, default_value = "0.05")]
87 max_resolution_for_interpolation: f64,
88 #[clap(long, default_value = "10")]
89 min_number_of_points_for_interpolation: i32,
90 },
91 GetState { name: String },
93 LoadCommands {
95 #[clap(value_parser)]
96 command_file_path: PathBuf,
97 },
98 List,
100 Speak { name: String, message: Vec<String> },
102 ExecuteCommand { command: Vec<String> },
104 GetNavigationCurrentPose,
106 SendNavigationGoal {
108 x: f64,
109 y: f64,
110 yaw: f64,
111 #[clap(short, long, default_value = "map")]
112 frame_id: String,
113 #[clap(short, long, default_value = "100.0")]
114 timeout_secs: f64,
115 },
116 CancelNavigationGoal,
118 SendBaseVelocity {
120 x: f64,
121 y: f64,
122 theta: f64,
123 #[clap(short, long, default_value = "1.0")]
124 duration_secs: f64,
125 },
126 #[clap(subcommand)]
128 ShellCompletion(ShellType),
129}
130
131#[derive(Debug, Parser, Clone, Copy)]
133#[clap(rename_all = "snake_case")]
134#[non_exhaustive]
135pub enum ShellType {
136 Zsh,
137 Bash,
138 Fish,
139 PowerShell,
140}
141
142impl From<ShellType> for Shell {
143 fn from(shell: ShellType) -> Shell {
144 match shell {
145 ShellType::Bash => Shell::Bash,
146 ShellType::Zsh => Shell::Zsh,
147 ShellType::Fish => Shell::Fish,
148 ShellType::PowerShell => Shell::PowerShell,
149 }
150 }
151}
152
153#[derive(Debug)]
154pub struct RobotCommandExecutor {}
155
156impl RobotCommandExecutor {
157 #[async_recursion]
158 #[allow(clippy::only_used_in_recursion)]
159 pub async fn execute<L, M, N>(
160 &self,
161 client: &RobotClient<L, M, N>,
162 command: &RobotCommand,
163 ) -> Result<(), OpenrrCommandError>
164 where
165 L: Localization,
166 M: MoveBase,
167 N: Navigation,
168 {
169 match &command {
170 RobotCommand::SendJoints {
171 name,
172 duration,
173 use_interpolation,
174 joint,
175 max_resolution_for_interpolation,
176 min_number_of_points_for_interpolation,
177 } => {
178 let mut positions = client.current_joint_positions(name)?;
179
180 let mut should_send = false;
181 for (index, position) in joint {
182 if *index < positions.len() {
183 should_send = true;
184 positions[*index] = *position;
185 }
186 }
187 if !should_send {
188 return Ok(());
189 }
190 if *use_interpolation {
191 client
192 .send_joint_positions_with_pose_interpolation(
193 name,
194 &positions,
195 *duration,
196 *max_resolution_for_interpolation,
197 *min_number_of_points_for_interpolation,
198 )?
199 .await?;
200 } else {
201 client
202 .send_joint_positions(name, &positions, *duration)?
203 .await?;
204 }
205 }
206 RobotCommand::SendJointsPose {
207 name,
208 pose_name,
209 duration,
210 } => {
211 client.send_joints_pose(name, pose_name, *duration)?.await?;
212 }
213 RobotCommand::MoveIk {
214 name,
215 x,
216 y,
217 z,
218 yaw,
219 pitch,
220 roll,
221 duration,
222 use_interpolation,
223 is_local,
224 max_resolution_for_interpolation,
225 min_number_of_points_for_interpolation,
226 } => {
227 if !client.is_ik_client(name) {
228 return Err(OpenrrCommandError::NoIkClient(name.clone()));
229 }
230 let mut should_send = false;
231 let current_pose = client.current_end_transform(name)?;
232 let target_pose = [
233 if let Some(x) = x {
234 should_send = true;
235 *x
236 } else if *is_local {
237 0.0
238 } else {
239 current_pose.translation.x
240 },
241 if let Some(y) = y {
242 should_send = true;
243 *y
244 } else if *is_local {
245 0.0
246 } else {
247 current_pose.translation.y
248 },
249 if let Some(z) = z {
250 should_send = true;
251 *z
252 } else if *is_local {
253 0.0
254 } else {
255 current_pose.translation.z
256 },
257 if let Some(roll) = roll {
258 should_send = true;
259 *roll
260 } else if *is_local {
261 0.0
262 } else {
263 current_pose.rotation.euler_angles().0
264 },
265 if let Some(pitch) = pitch {
266 should_send = true;
267 *pitch
268 } else if *is_local {
269 0.0
270 } else {
271 current_pose.rotation.euler_angles().1
272 },
273 if let Some(yaw) = yaw {
274 should_send = true;
275 *yaw
276 } else if *is_local {
277 0.0
278 } else {
279 current_pose.rotation.euler_angles().2
280 },
281 ];
282 if !should_send {
283 return Ok(());
284 }
285 let target_pose = isometry(
286 target_pose[0],
287 target_pose[1],
288 target_pose[2],
289 target_pose[3],
290 target_pose[4],
291 target_pose[5],
292 );
293
294 let target_pose = if *is_local {
295 client.transform(name, &target_pose)?
296 } else {
297 target_pose
298 };
299 if *use_interpolation {
300 client
301 .move_ik_with_interpolation(
302 name,
303 &target_pose,
304 *duration,
305 *max_resolution_for_interpolation,
306 *min_number_of_points_for_interpolation,
307 )?
308 .await?
309 } else {
310 client.move_ik(name, &target_pose, *duration)?.await?
311 }
312 }
313 RobotCommand::GetState { name } => {
314 println!("Joint names : {:?}", client.joint_names(name)?);
315 println!(
316 "Joint positions : {:?}",
317 client.current_joint_positions(name)?
318 );
319 if client.is_ik_client(name) {
320 let pose = client.current_end_transform(name)?;
321 println!("End pose");
322 println!(" translation = {:?}", pose.translation.vector.data);
323 println!(" rotation = {:?}", pose.rotation.euler_angles());
324 }
325 }
326 RobotCommand::LoadCommands { command_file_path } => {
327 for command in load_command_file_and_filter(command_file_path.clone())? {
328 let command_parsed_iter = command.split_whitespace();
329 let read_opt = RobotCommand::parse_from(command_parsed_iter);
331 info!("Executing {command}");
333 self.execute(client, &read_opt).await?;
334 }
335 }
336 RobotCommand::List => {
337 println!("Raw joint trajectory clients");
338 for name in client.raw_joint_trajectory_clients_names() {
339 println!(" {name}");
340 }
341 println!("Joint trajectory clients");
342 for name in client.joint_trajectory_clients_names() {
343 println!(" {name}");
344 }
345 println!("Collision avoidance clients");
346 for name in client.collision_avoidance_clients_names() {
347 println!(" {name}");
348 }
349 println!("Collision check clients");
350 for name in client.collision_check_clients_names() {
351 println!(" {name}");
352 }
353 println!("Ik clients");
354 for name in client.ik_clients_names() {
355 println!(" {name}");
356 }
357 }
358 RobotCommand::Speak { name, message } => {
359 client.speak(name, &message.join(" "))?.await?;
363 }
364 RobotCommand::ExecuteCommand { command } => {
365 let command = filter_escape_double_quote(command);
366 let mut iter = command.iter();
367 let cmd_str = iter
368 .next()
369 .ok_or_else(|| OpenrrCommandError::NoCommand(command.to_owned()))?;
370 let output = Command::new(cmd_str).args(iter).output().map_err(|e| {
371 OpenrrCommandError::CommandExecutionFailure(command.to_owned(), e)
372 })?;
373 if output.status.success() {
374 info!("{}", String::from_utf8_lossy(&output.stdout));
375 } else {
376 error!("{}", String::from_utf8_lossy(&output.stdout));
377 error!("{}", String::from_utf8_lossy(&output.stderr));
378 return Err(OpenrrCommandError::CommandFailure(
379 command.to_owned(),
380 String::from_utf8_lossy(&output.stderr).to_string(),
381 ));
382 }
383 }
384 RobotCommand::GetNavigationCurrentPose => {
385 println!("Base Pose {}", client.current_pose("")?);
386 }
387 RobotCommand::SendNavigationGoal {
388 x,
389 y,
390 yaw,
391 frame_id,
392 timeout_secs,
393 } => {
394 client
395 .send_goal_pose(
396 Isometry2::new(Vector2::new(*x, *y), *yaw),
397 frame_id,
398 Duration::from_secs_f64(*timeout_secs),
399 )?
400 .await?;
401 }
402 RobotCommand::CancelNavigationGoal => {
403 client.cancel()?;
404 }
405 RobotCommand::SendBaseVelocity {
406 x,
407 y,
408 theta,
409 duration_secs,
410 } => {
411 let start = Instant::now();
412 let duration = Duration::from_secs_f64(*duration_secs);
413 let sleep_duration = Duration::from_secs_f64(0.01);
414 while start.elapsed() < duration {
415 client.send_velocity(&BaseVelocity::new(*x, *y, *theta))?;
416 sleep(sleep_duration);
417 }
418 }
419 _ => {
420 panic!("not supported {command:?}");
421 }
422 }
423 Ok(())
424 }
425
426 pub async fn run_interactive_shell<L, M, N>(
428 &self,
429 client: &RobotClient<L, M, N>,
430 ) -> Result<(), OpenrrCommandError>
431 where
432 L: Localization,
433 M: MoveBase,
434 N: Navigation,
435 {
436 let mut rl = DefaultEditor::with_config(
437 rustyline::Config::builder().auto_add_history(true).build(),
438 )?;
439 const HISTORY_FILE_NAME: &str = "openrr_apps_robot_command_log.txt";
440 let _ = rl.load_history(HISTORY_FILE_NAME);
442 loop {
443 let readline = rl.readline("\x1b[1;32m>> \x1b[0m");
444 match readline {
445 Ok(line) => {
446 let line_with_arg0 = format!("dummy {line}");
448 let command_parsed_iter = line_with_arg0.split_whitespace();
449 if let Ok(command) = RobotCommand::try_parse_from(command_parsed_iter) {
451 if let Err(e) = self.execute(client, &command).await {
452 println!("failed to execute: {e:?}");
453 }
454 } else if !line.is_empty() {
455 println!("failed to parse: {line:?}");
456 }
457 }
458 Err(ReadlineError::Interrupted) => {
459 println!("CTRL-C");
460 break;
461 }
462 Err(ReadlineError::Eof) => {
463 println!("CTRL-D");
464 break;
465 }
466 Err(err) => {
467 println!("Error: {err:?}");
468 break;
469 }
470 }
471 }
472 if let Err(err) = rl.save_history(HISTORY_FILE_NAME) {
473 println!("failed to save history {HISTORY_FILE_NAME}: {err:?}");
474 }
475 Ok(())
476 }
477}
478
479pub fn load_command_file_and_filter(file_path: PathBuf) -> Result<Vec<String>, OpenrrCommandError> {
480 let file = File::open(&file_path)
481 .map_err(|e| OpenrrCommandError::CommandFileOpenFailure(file_path, e.to_string()))?;
482 let buf = BufReader::new(file);
483 Ok(buf
484 .lines()
485 .map(|line| line.expect("Could not parse line"))
486 .filter(|command| {
487 let command_parsed_iter = command.split_whitespace();
488 command_parsed_iter.clone().count() > 0
490 && command_parsed_iter
491 .clone()
492 .next()
493 .unwrap()
494 .find('#')
495 .is_none()
496 })
497 .collect())
498}
499
500fn filter_escape_double_quote(robot_command: &[String]) -> Vec<String> {
501 let mut is_concatenation = false;
502 let mut command_vector: Vec<String> = Vec::new();
503
504 for element in robot_command {
505 let command_element = element.replace('\"', "");
506 if is_concatenation {
507 let new_command = command_vector
508 .pop()
509 .expect("Parse double quote logic error. Vector command_vector is empty.");
510 command_vector.push(format!("{new_command} {command_element}"));
511 } else {
512 command_vector.push(command_element.to_string());
513 }
514 if element.match_indices('\"').count() == 1 {
515 is_concatenation = !is_concatenation;
516 }
517 }
518 command_vector
519}
520
521#[cfg(test)]
522mod test {
523 use super::*;
524 #[test]
525 fn test_parse_joints() {
526 let val: (usize, usize) = parse_joints("0=2").unwrap();
527 assert_eq!(val.0, 0);
528 assert_eq!(val.1, 2);
529 }
530
531 #[test]
532 fn test_filter_escape_double_quote() {
533 let expected_command: Vec<String> = vec![
535 "command".to_string(),
536 "foo/bar".to_string(),
537 "baz qux".to_string(),
538 ];
539
540 let robot_command: Vec<String> = vec![
541 "command".to_string(),
542 "foo/bar".to_string(),
543 "\"baz".to_string(),
544 "qux\"".to_string(),
545 ];
546 let result_command = filter_escape_double_quote(&robot_command);
547
548 assert_eq!(expected_command, result_command);
549
550 let expected_dict_command: Vec<String> = vec![
552 "command".to_string(),
553 "-f".to_string(),
554 "{ type: Message, value: 1.0 }".to_string(),
555 ];
556 let robot_dict_command: Vec<String> = vec![
557 "command".to_string(),
558 "-f".to_string(),
559 "\"{".to_string(),
560 "type:".to_string(),
561 "Message,".to_string(),
562 "value:".to_string(),
563 "1.0".to_string(),
564 "}\"".to_string(),
565 ];
566 let result_dict_command = filter_escape_double_quote(&robot_dict_command);
567
568 assert_eq!(expected_dict_command, result_dict_command);
569 }
570}