openrr_apps_robot_command/
robot_command.rs
1use std::path::PathBuf;
2
3use anyhow::Result;
4use clap::{CommandFactory, Parser};
5use clap_complete::Shell;
6use openrr_apps::{
7 utils::{init_tracing, init_tracing_with_file_appender, LogConfig},
8 Error, RobotConfig,
9};
10use openrr_client::BoxRobotClient;
11use openrr_command::{RobotCommand, RobotCommandExecutor};
12use tracing::info;
13
14#[derive(Parser, Debug)]
16#[clap(name = env!("CARGO_BIN_NAME"))]
17struct RobotCommandArgs {
18 #[clap(short, long, value_parser)]
20 config_path: Option<PathBuf>,
21 #[clap(long)]
24 config: Option<String>,
25 #[clap(subcommand)]
26 command: Option<RobotCommand>,
27 #[clap(long)]
29 show_default_config: bool,
30 #[clap(short, long)]
32 interactive: bool,
33 #[clap(long, value_parser)]
35 log_directory: Option<PathBuf>,
36}
37
38fn shell_completion(shell_type: openrr_command::ShellType) {
39 clap_complete::generate(
40 Shell::from(shell_type),
41 &mut RobotCommandArgs::command(),
42 env!("CARGO_BIN_NAME"),
43 &mut std::io::stdout(),
44 );
45}
46
47#[tokio::main]
48async fn main() -> Result<()> {
49 let args = RobotCommandArgs::parse();
50 if args.log_directory.is_none() {
51 init_tracing();
52 }
53 #[cfg(not(feature = "ros"))]
54 let _guard = args.log_directory.as_ref().map(|log_directory| {
55 init_tracing_with_file_appender(
56 LogConfig {
57 directory: log_directory.to_path_buf(),
58 ..Default::default()
59 },
60 env!("CARGO_BIN_NAME").to_string(),
61 )
62 });
63
64 info!("ParsedArgs {args:?}");
65
66 if args.show_default_config {
67 print!("{}", toml::to_string(&RobotConfig::default()).unwrap());
68 return Ok(());
69 }
70
71 if let Some(RobotCommand::ShellCompletion(shell_type)) = args.command.as_ref() {
73 shell_completion(*shell_type);
74 return Ok(());
75 }
76
77 let config_path = openrr_apps::utils::get_apps_robot_config(args.config_path);
78
79 let robot_config =
80 openrr_apps::utils::resolve_robot_config(config_path.as_deref(), args.config.as_deref())?;
81
82 openrr_apps::utils::init_with_anonymize(env!("CARGO_BIN_NAME"), &robot_config);
83 #[cfg(feature = "ros")]
84 let _guard = args.log_directory.map(|log_directory| {
85 init_tracing_with_file_appender(
86 LogConfig {
87 directory: log_directory,
88 ..Default::default()
89 },
90 if robot_config.has_ros_clients() {
91 arci_ros::name()
92 } else {
93 env!("CARGO_BIN_NAME").to_string()
94 },
95 )
96 });
97 let client: BoxRobotClient = robot_config.create_robot_client()?;
98 let executor = RobotCommandExecutor {};
99
100 if args.interactive {
101 Ok(executor.run_interactive_shell(&client).await?)
102 } else {
103 let command = args.command.ok_or(Error::NoCommand)?;
104 Ok(executor.execute(&client, &command).await?)
105 }
106}
107
108#[cfg(test)]
109mod tests {
110 use std::{env, path::Path};
111
112 use openrr_command::load_command_file_and_filter;
113 use tracing::log::error;
114
115 use super::*;
116
117 #[test]
118 fn parse_args() {
119 let bin = env!("CARGO_BIN_NAME");
120 assert!(RobotCommandArgs::try_parse_from([bin]).is_ok());
121 assert!(RobotCommandArgs::try_parse_from([bin, "--show-default-config"]).is_ok());
122 assert!(RobotCommandArgs::try_parse_from([bin, "--config-path", "path", "list"]).is_ok());
123 assert!(RobotCommandArgs::try_parse_from([
124 bin,
125 "--show-default-config",
126 "--config-path",
127 "path"
128 ])
129 .is_ok());
130 }
131
132 #[test]
133 fn assert_app() {
134 RobotCommandArgs::command().debug_assert();
135 }
136
137 const COMMAND_PATHS: [&str; 11] = [
138 "command/sample_cmd_urdf_viz.txt",
139 "command/pr2_cmd_collision.txt",
140 "command/pr2_cmd_ik.txt",
141 "command/pr2_cmd_joints.txt",
142 "command/pr2_cmd_ros.txt",
143 "command/pr2_cmd_urdf_viz.txt",
144 "command/ur10_cmd_collision.txt",
145 "command/ur10_cmd_ik.txt",
146 "command/ur10_cmd_joints.txt",
147 "command/ur10_cmd_ros.txt",
148 "command/ur10_cmd_urdf_viz.txt",
149 ];
150
151 #[test]
152 fn assert_commands() {
153 for command_path in COMMAND_PATHS {
154 let bin = env!("CARGO_BIN_NAME");
155 let manifest_dir = Path::new(env!("CARGO_MANIFEST_DIR"));
156
157 let config_path = manifest_dir.join("config/sample_robot_client_for_urdf_viz.toml");
158 let config_path_arg = "--config-path=".to_string() + config_path.to_str().unwrap();
159 let sample_command_path = manifest_dir.join(command_path);
160
161 let sample_command = RobotCommandArgs::try_parse_from([
162 bin,
163 config_path_arg.as_str(),
164 "load_commands",
165 sample_command_path.to_str().unwrap(),
166 ])
167 .unwrap();
168 let mut results = Vec::new();
169
170 let command = sample_command.command.ok_or(Error::NoCommand).unwrap();
171
172 check_command(&command, &mut results, command_path);
173
174 for result in results {
175 assert!(result);
176 }
177 }
178 }
179
180 fn check_command(command: &RobotCommand, log: &mut Vec<bool>, command_path: &str) {
181 match &command {
182 RobotCommand::SendJoints {
183 name: _,
184 duration,
185 use_interpolation: _,
186 joint: _,
187 max_resolution_for_interpolation: _,
188 min_number_of_points_for_interpolation: _,
189 } => {
190 log.push(*duration >= 0f64);
191 }
192 RobotCommand::SendJointsPose {
193 name: _,
194 pose_name: _,
195 duration,
196 } => {
197 log.push(*duration >= 0f64);
198 }
199 RobotCommand::MoveIk {
200 name: _,
201 x: _,
202 y: _,
203 z: _,
204 yaw: _,
205 pitch: _,
206 roll: _,
207 duration,
208 use_interpolation: _,
209 is_local: _,
210 max_resolution_for_interpolation: _,
211 min_number_of_points_for_interpolation: _,
212 } => {
213 log.push(*duration >= 0f64);
214 }
215 RobotCommand::GetState { name: _ } => log.push(true),
216 RobotCommand::LoadCommands { command_file_path } => {
217 let target_dir = Path::new(env!("CARGO_MANIFEST_DIR"));
218 let target_command_file_path = target_dir.join(command_path);
219 log.push(*command_file_path == target_command_file_path);
220
221 for command in load_command_file_and_filter(target_command_file_path).unwrap() {
222 let command_parsed_iter = command.split_whitespace();
223 let read_opt = RobotCommand::try_parse_from(command_parsed_iter);
224 match read_opt {
225 Ok(robot_command) => {
226 check_command(&robot_command, log, command_path);
227 }
228 Err(err) => {
229 error!("Error in {:?}: {}", command_file_path, err);
230 log.push(false);
231 }
232 }
233 }
234 }
235 RobotCommand::List => {
236 log.push(true);
237 }
238 RobotCommand::Speak {
239 name: _,
240 message: _,
241 } => {
242 log.push(true);
243 }
244 RobotCommand::ExecuteCommand { command: _ } => {
245 log.push(true);
246 }
247 RobotCommand::GetNavigationCurrentPose => {
248 log.push(true);
249 }
250 RobotCommand::SendNavigationGoal {
251 x: _,
252 y: _,
253 yaw: _,
254 frame_id: _,
255 timeout_secs: _,
256 } => {
257 log.push(true);
258 }
259 RobotCommand::CancelNavigationGoal => {
260 log.push(true);
261 }
262 RobotCommand::SendBaseVelocity {
263 x: _,
264 y: _,
265 theta: _,
266 duration_secs,
267 } => {
268 log.push(*duration_secs >= 0f64);
269 }
270 _ => {
271 log.push(false);
272 }
273 }
274 }
275}