1use std::{
2 collections::HashMap,
3 env, fmt, fs,
4 ops::Not,
5 path::{Path, PathBuf},
6 sync::Arc,
7};
8
9use anyhow::format_err;
10use arci::{JointTrajectoryClient, Localization, MoveBase, Navigation, Speaker};
11#[cfg(feature = "ros")]
12use arci_ros::{
13 RosCmdVelMoveBase, RosCmdVelMoveBaseConfig, RosControlActionClientConfig,
14 RosControlClientConfig, RosEspeakClient, RosEspeakClientConfig, RosLocalizationClient,
15 RosLocalizationClientConfig, RosNavClient, RosNavClientConfig,
16};
17use arci_speak_audio::AudioSpeaker;
18use arci_speak_cmd::LocalCommand;
19use arci_urdf_viz::{UrdfVizWebClient, UrdfVizWebClientConfig};
20use openrr_client::{OpenrrClientsConfig, PrintSpeaker, RobotClient};
21use openrr_plugin::PluginProxy;
22use openrr_tracing::Tracing;
23use schemars::JsonSchema;
24use serde::{Deserialize, Serialize};
25use tracing::{debug, error, info};
26
27use crate::Error;
28
29#[derive(Debug, Clone, Copy, PartialEq, Eq, Serialize, Deserialize, JsonSchema)]
30#[serde(rename_all = "kebab-case")]
31pub enum BuiltinClient {
32 Ros,
34 UrdfViz,
36}
37
38#[derive(Debug, Clone, PartialEq, Eq, Serialize, Deserialize, JsonSchema)]
39#[serde(untagged)]
40pub enum ClientKind {
41 Builtin(BuiltinClient),
43 Plugin(String),
45 Auto(bool),
48}
49
50impl ClientKind {
51 #[cfg(feature = "ros")]
55 fn is_builtin_ros(&self) -> bool {
56 matches!(self, Self::Builtin(BuiltinClient::Ros))
57 }
58
59 fn is_auto(&self) -> bool {
60 matches!(self, Self::Auto(true))
61 }
62}
63
64impl Default for ClientKind {
65 fn default() -> Self {
66 Self::Auto(true)
67 }
68}
69
70#[derive(Debug, Clone, Default, Serialize, Deserialize, JsonSchema)]
71#[serde(tag = "type", content = "args")]
72#[serde(deny_unknown_fields)]
73#[non_exhaustive] pub enum SpeakConfig {
75 #[default]
76 Print,
77 Command,
78 #[cfg(feature = "ros")]
79 RosEspeak {
80 config: RosEspeakClientConfig,
81 },
82 #[doc(hidden)]
85 #[cfg(not(feature = "ros"))]
86 RosEspeak {
87 #[schemars(schema_with = "unimplemented_schema")]
88 config: toml::Value,
89 },
90 Audio {
91 map: HashMap<String, PathBuf>,
92 },
93}
94
95impl SpeakConfig {
96 pub fn build(&self) -> Result<Box<dyn Speaker>, Error> {
97 Ok(match self {
98 SpeakConfig::RosEspeak { config } => self.create_ros_espeak_client(config),
99 SpeakConfig::Audio { map } => self.create_audio_speaker(map.clone())?,
100 SpeakConfig::Command => self.create_local_command_speaker(),
101 SpeakConfig::Print => self.create_print_speaker(),
102 })
103 }
104
105 fn create_print_speaker(&self) -> Box<dyn Speaker> {
106 Box::new(arci::Lazy::new(move || {
107 debug!("create_print_speaker: creating PrintSpeaker");
108 Ok(PrintSpeaker::new())
109 }))
110 }
111
112 fn create_local_command_speaker(&self) -> Box<dyn Speaker> {
113 Box::new(arci::Lazy::new(move || {
114 debug!("create_local_command_speaker: creating LocalCommand");
115 Ok(LocalCommand::new())
116 }))
117 }
118
119 fn create_audio_speaker(
120 &self,
121 mut hash_map: HashMap<String, PathBuf>,
122 ) -> Result<Box<dyn Speaker>, Error> {
123 for path in hash_map.values_mut() {
124 *path = openrr_config::evaluate(path.to_str().unwrap(), None)
125 .map_err(arci::Error::Other)?
126 .into();
127 }
128 Ok(Box::new(arci::Lazy::new(move || {
129 debug!("create_audio_speaker: creating AudioSpeaker");
130 Ok(AudioSpeaker::new(hash_map))
131 })))
132 }
133
134 #[cfg(feature = "ros")]
135 fn create_ros_espeak_client(&self, config: &RosEspeakClientConfig) -> Box<dyn Speaker> {
136 let topic = config.topic.to_string();
137 Box::new(arci::Lazy::new(move || {
138 debug!("create_ros_espeak_client: creating RosEspeakClient");
139 Ok(RosEspeakClient::new(&topic))
140 }))
141 }
142
143 #[cfg(not(feature = "ros"))]
144 fn create_ros_espeak_client(&self, _config: &toml::Value) -> Box<dyn Speaker> {
145 unreachable!()
146 }
147}
148
149#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)]
150#[serde(deny_unknown_fields)]
151pub struct PluginConfig {
152 pub path: PathBuf,
156 pub instances: Vec<PluginInstance>,
157}
158
159impl PluginConfig {
160 fn find_instances_by_name<'a>(
161 map: &'a HashMap<String, Self>,
162 instance_name: &'a str,
163 instance_kind: PluginInstanceKind,
164 ) -> impl Iterator<Item = (&'a str, &'a PluginInstance)> {
165 map.iter().flat_map(move |(plugin_name, plugin_config)| {
166 plugin_config
167 .instances
168 .iter()
169 .filter(move |instance| {
170 instance.name == instance_name && instance.type_ == instance_kind
171 })
172 .map(move |instance| (plugin_name.as_str(), instance))
173 })
174 }
175
176 fn find_instances_by_kind(
177 map: &HashMap<String, Self>,
178 instance_kind: PluginInstanceKind,
179 ) -> impl Iterator<Item = (&str, &PluginInstance)> {
180 map.iter().flat_map(move |(plugin_name, plugin_config)| {
181 plugin_config
182 .instances
183 .iter()
184 .filter(move |instance| instance.type_ == instance_kind)
185 .map(move |instance| (plugin_name.as_str(), instance))
186 })
187 }
188
189 fn resolve_instance<'a>(
190 map: &'a HashMap<String, Self>,
191 instance_name: Option<&'a str>,
192 instance_kind: PluginInstanceKind,
193 ) -> Result<(&'a str, &'a PluginInstance), Error> {
194 let instances: Vec<_> = if let Some(instance_name) = instance_name {
195 Self::find_instances_by_name(map, instance_name, instance_kind).collect()
196 } else {
197 Self::find_instances_by_kind(map, instance_kind).collect()
198 };
199
200 if instances.is_empty() {
201 return Err(Error::NoPluginInstance {
202 name: instance_name.unwrap_or_default().to_string(),
203 kind: instance_kind.to_string(),
204 });
205 }
206 if instances.len() == 1 {
207 return Ok(instances[0]);
208 }
209
210 if let Some(instance_name) = instance_name {
211 Err(Error::DuplicateInstance(format!(
212 "Multiple {instance_kind:?} plugin instances {instance_name:?} are found. Consider renaming one of the instances",
213 )))
214 } else {
215 Err(Error::DuplicateInstance(format!(
216 "Multiple plugin instances for {instance_kind:?} are found. Consider specifying the instance to use",
217 )))
218 }
219 }
220}
221
222#[allow(clippy::needless_borrows_for_generic_args)] pub(crate) fn resolve_plugin_path(
224 plugin_path: &mut PathBuf,
225 base_path: impl AsRef<Path>,
226) -> Result<(), Error> {
227 *plugin_path = openrr_client::resolve_relative_path(base_path, &plugin_path)?;
228 if plugin_path.extension().is_none() {
229 plugin_path.set_extension(env::consts::DLL_EXTENSION);
230 }
231 Ok(())
232}
233
234#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)]
235#[serde(deny_unknown_fields)]
236pub struct PluginInstance {
237 pub name: String,
239 #[serde(rename = "type")]
241 pub type_: PluginInstanceKind,
242 pub args: Option<String>,
244 pub args_from_path: Option<PathBuf>,
246}
247
248impl PluginInstance {
249 pub fn load_args(&self) -> Result<String, Error> {
250 if let Some(path) = &self.args_from_path {
251 fs::read_to_string(path).map_err(|e| Error::NoFile(path.to_owned(), e))
252 } else {
253 Ok(self.args.clone().unwrap_or_default())
254 }
255 }
256
257 fn create_lazy_instance<T, F>(
258 &self,
259 plugins: &mut PluginMap,
260 plugin_name: &str,
261 f: F,
262 ) -> Result<arci::Lazy<'static, T>, Error>
263 where
264 T: fmt::Debug,
265 F: FnOnce(&PluginProxy, String) -> Result<Option<T>, arci::Error> + Send + Sync + 'static,
266 {
267 let plugin = if let Some(plugin) = plugins.load(plugin_name)? {
268 plugin
269 } else {
270 return Err(Error::NoPluginInstance {
271 name: plugin_name.to_string(),
272 kind: self.type_.to_string(),
273 });
274 };
275 let args = self.load_args()?;
276 let plugin_name = plugin_name.to_string();
277 let instance_name = self.name.clone();
278 let instance_kind = self.type_;
279 Ok(arci::Lazy::new(move || match f(&plugin, args) {
280 Ok(Some(instance)) => {
281 info!(
282 "created `{instance_kind:?}` instance `{instance_name}` from plugin `{plugin_name}`",
283 );
284 Ok(instance)
285 }
286 res => instance_create_error(res, instance_kind, instance_name, plugin_name)?,
287 }))
288 }
289}
290
291#[derive(Debug, Clone, Copy, PartialEq, Eq, Serialize, Deserialize, JsonSchema)]
293#[serde(deny_unknown_fields)]
294#[non_exhaustive]
295pub enum PluginInstanceKind {
296 JointTrajectoryClient,
297 Localization,
298 MoveBase,
299 Navigation,
300 Speaker,
301}
302
303impl fmt::Display for PluginInstanceKind {
304 fn fmt(&self, f: &mut fmt::Formatter<'_>) -> fmt::Result {
305 write!(f, "{self:?}")
306 }
307}
308
309#[derive(Debug, Default)]
310pub struct PluginMap {
311 path: HashMap<String, PathBuf>,
312 cache: HashMap<String, Arc<PluginProxy>>,
313}
314
315impl PluginMap {
316 pub fn load(&mut self, name: impl AsRef<str>) -> Result<Option<Arc<PluginProxy>>, arci::Error> {
317 let name = name.as_ref();
318 if let Some((name, path)) = self.path.remove_entry(name) {
319 let plugin = Arc::new(PluginProxy::from_path(path)?);
320 self.cache.insert(name, plugin.clone());
321 Ok(Some(plugin))
322 } else {
323 Ok(self.cache.get(name).cloned())
324 }
325 }
326}
327
328impl<S: Into<String>, P: Into<PathBuf>> FromIterator<(S, P)> for PluginMap {
329 fn from_iter<T: IntoIterator<Item = (S, P)>>(iter: T) -> Self {
330 let path: HashMap<_, _> = iter
331 .into_iter()
332 .map(|(name, path)| (name.into(), path.into()))
333 .collect();
334 Self {
335 cache: HashMap::with_capacity(path.len() / 2),
336 path,
337 }
338 }
339}
340
341#[derive(Debug, Clone, Default, Serialize, Deserialize, JsonSchema)]
342#[serde(deny_unknown_fields)]
343#[non_exhaustive] pub struct RobotConfig {
345 pub joint_trajectory_clients: Option<Vec<String>>,
350 pub speakers: Option<Vec<String>>,
352 #[serde(skip_serializing_if = "ClientKind::is_auto")]
354 #[serde(default)]
355 pub localization: ClientKind,
356 #[serde(skip_serializing_if = "ClientKind::is_auto")]
358 #[serde(default)]
359 pub move_base: ClientKind,
360 #[serde(skip_serializing_if = "ClientKind::is_auto")]
362 #[serde(default)]
363 pub navigation: ClientKind,
364
365 #[cfg(feature = "ros")]
366 #[serde(default)]
367 #[serde(skip_serializing_if = "Vec::is_empty")]
369 pub ros_clients_configs: Vec<RosControlClientConfig>,
370 #[cfg(not(feature = "ros"))]
372 #[serde(default)]
373 #[serde(skip_serializing_if = "Vec::is_empty")]
374 #[schemars(schema_with = "unimplemented_schema")]
375 ros_clients_configs: Vec<toml::Value>,
376
377 #[cfg(feature = "ros")]
378 #[serde(default)]
379 #[serde(skip_serializing_if = "Vec::is_empty")]
381 pub ros_action_clients_configs: Vec<RosControlActionClientConfig>,
382 #[cfg(not(feature = "ros"))]
384 #[serde(default)]
385 #[serde(skip_serializing_if = "Vec::is_empty")]
386 #[schemars(schema_with = "unimplemented_schema")]
387 ros_action_clients_configs: Vec<toml::Value>,
388
389 #[serde(default)]
390 #[serde(skip_serializing_if = "Vec::is_empty")]
392 pub urdf_viz_clients_configs: Vec<UrdfVizWebClientConfig>,
393
394 #[serde(default)]
395 pub speak_configs: HashMap<String, SpeakConfig>,
396
397 #[cfg(feature = "ros")]
398 pub ros_cmd_vel_move_base_client_config: Option<RosCmdVelMoveBaseConfig>,
399 #[cfg(not(feature = "ros"))]
401 #[schemars(schema_with = "unimplemented_schema")]
402 ros_cmd_vel_move_base_client_config: Option<toml::Value>,
403
404 #[cfg(feature = "ros")]
405 pub ros_navigation_client_config: Option<RosNavClientConfig>,
406 #[cfg(not(feature = "ros"))]
408 #[schemars(schema_with = "unimplemented_schema")]
409 ros_navigation_client_config: Option<toml::Value>,
410
411 #[cfg(feature = "ros")]
412 pub ros_localization_client_config: Option<RosLocalizationClientConfig>,
413 #[cfg(not(feature = "ros"))]
415 #[schemars(schema_with = "unimplemented_schema")]
416 ros_localization_client_config: Option<toml::Value>,
417
418 #[serde(default)]
419 pub openrr_clients_config: OpenrrClientsConfig,
420
421 #[serde(default)]
422 pub openrr_tracing_config: OpenrrTracingConfig,
423
424 #[serde(default)]
425 pub plugins: HashMap<String, PluginConfig>,
426}
427
428#[derive(Debug, Clone, Default, Serialize, Deserialize, JsonSchema)]
429#[serde(deny_unknown_fields)]
430pub struct OpenrrTracingConfig {
431 #[serde(skip_serializing_if = "Not::not")]
433 #[serde(default)]
434 pub localization: bool,
435 #[serde(skip_serializing_if = "Not::not")]
437 #[serde(default)]
438 pub move_base: bool,
439 #[serde(skip_serializing_if = "Not::not")]
441 #[serde(default)]
442 pub navigation: bool,
443}
444
445#[cfg(not(feature = "ros"))]
447fn unimplemented_schema(_gen: &mut schemars::gen::SchemaGenerator) -> schemars::schema::Schema {
448 unimplemented!()
449}
450
451impl RobotConfig {
452 const DEFAULT_SPEAKER_NAME: &'static str = "Default";
453
454 #[cfg(feature = "ros")]
459 pub fn has_ros_clients(&self) -> bool {
460 let mut has_ros_clients = false;
461 let speak_configs = self.speak_configs.clone();
462 for (_, speak_config) in speak_configs {
463 has_ros_clients |= matches!(speak_config, SpeakConfig::RosEspeak { .. });
464 }
465 has_ros_clients |= !self.ros_clients_configs.is_empty();
466 has_ros_clients |= !self.ros_action_clients_configs.is_empty();
467 has_ros_clients |= self.move_base.is_builtin_ros()
468 || (self.move_base.is_auto() && self.ros_cmd_vel_move_base_client_config.is_some());
469 has_ros_clients |= self.navigation.is_builtin_ros()
470 || (self.navigation.is_auto() && self.ros_navigation_client_config.is_some());
471 has_ros_clients |= self.localization.is_builtin_ros()
472 || (self.localization.is_auto() && self.ros_localization_client_config.is_some());
473 has_ros_clients
474 }
475
476 #[cfg(not(feature = "ros"))]
477 pub fn has_ros_clients(&self) -> bool {
478 false
479 }
480
481 pub fn create_robot_client<L, M, N>(&self) -> Result<RobotClient<L, M, N>, Error>
482 where
483 L: Localization + From<Box<dyn Localization>>,
484 M: MoveBase + From<Box<dyn MoveBase>>,
485 N: Navigation + From<Box<dyn Navigation>>,
486 {
487 let mut plugins: PluginMap = self
488 .plugins
489 .iter()
490 .map(|(plugin_name, config)| (plugin_name, &config.path))
491 .collect();
492
493 let joint_trajectory_clients = self.create_raw_joint_trajectory_clients(&mut plugins)?;
494 let speakers = self.create_speakers(&mut plugins)?;
495 let localization = self.create_localization(&mut plugins)?;
496 let move_base = self.create_move_base(&mut plugins)?;
497 let navigation = self.create_navigation(&mut plugins)?;
498
499 Ok(RobotClient::new(
500 self.openrr_clients_config.clone(),
501 joint_trajectory_clients,
502 speakers,
503 localization.map(L::from),
504 move_base.map(M::from),
505 navigation.map(N::from),
506 )?)
507 }
508
509 fn create_localization_urdf_viz(&self) -> Box<dyn Localization> {
510 let loc = arci::Lazy::new(move || {
511 debug!("create_localization_urdf_viz: creating UrdfVizWebClient");
512 Ok(UrdfVizWebClient::default())
513 });
514 if self.openrr_tracing_config.localization {
515 Box::new(Tracing::new(loc))
516 } else {
517 Box::new(loc)
518 }
519 }
520
521 #[cfg(feature = "ros")]
522 fn create_localization_ros(&self) -> Option<Box<dyn Localization>> {
523 let config = self.ros_localization_client_config.clone()?;
524 let loc = arci::Lazy::new(move || {
525 debug!("create_localization_ros: creating RosLocalizationClient");
526 Ok(RosLocalizationClient::new_from_config(config))
527 });
528 if self.openrr_tracing_config.localization {
529 Some(Box::new(Tracing::new(loc)))
530 } else {
531 Some(Box::new(loc))
532 }
533 }
534
535 #[cfg(not(feature = "ros"))]
536 fn create_localization_ros(&self) -> Option<Box<dyn Localization>> {
537 unreachable!()
538 }
539
540 fn create_localization(
541 &self,
542 plugins: &mut PluginMap,
543 ) -> Result<Option<Box<dyn Localization>>, Error> {
544 let (plugin_name, instance) = match &self.localization {
545 ClientKind::Auto(false) => return Ok(None),
546 ClientKind::Auto(true) => {
547 if self.ros_localization_client_config.is_some() {
548 return Ok(self.create_localization_ros());
549 }
550 match PluginConfig::resolve_instance(
551 &self.plugins,
552 None,
553 PluginInstanceKind::Localization,
554 ) {
555 Err(Error::NoPluginInstance { .. }) => {
556 if self.has_ros_clients() {
561 return Ok(None);
562 }
563 return Ok(Some(self.create_localization_urdf_viz()));
564 }
565 res => res?,
566 }
567 }
568 ClientKind::Builtin(BuiltinClient::Ros) => {
569 return Ok(self.create_localization_ros());
570 }
571 ClientKind::Builtin(BuiltinClient::UrdfViz) => {
572 return Ok(Some(self.create_localization_urdf_viz()));
573 }
574 ClientKind::Plugin(instance_name) => PluginConfig::resolve_instance(
575 &self.plugins,
576 Some(instance_name),
577 PluginInstanceKind::Localization,
578 )?,
579 };
580
581 Ok(Some(Box::new(instance.create_lazy_instance(
582 plugins,
583 plugin_name,
584 PluginProxy::new_localization,
585 )?)))
586 }
587
588 fn create_navigation_urdf_viz(&self) -> Box<dyn Navigation> {
589 let nav = arci::Lazy::new(move || {
590 debug!("create_navigation_urdf_viz: creating UrdfVizWebClient");
591 Ok(UrdfVizWebClient::default())
592 });
593 if self.openrr_tracing_config.navigation {
594 Box::new(Tracing::new(nav))
595 } else {
596 Box::new(nav)
597 }
598 }
599
600 #[cfg(feature = "ros")]
601 fn create_navigation_ros(&self) -> Option<Box<dyn Navigation>> {
602 let config = self.ros_navigation_client_config.clone()?;
603 let nav = arci::Lazy::new(move || {
604 debug!("create_navigation_ros: creating RosNavClient");
605 Ok(RosNavClient::new_from_config(config))
606 });
607 if self.openrr_tracing_config.navigation {
608 Some(Box::new(Tracing::new(nav)))
609 } else {
610 Some(Box::new(nav))
611 }
612 }
613
614 #[cfg(not(feature = "ros"))]
615 fn create_navigation_ros(&self) -> Option<Box<dyn Navigation>> {
616 unreachable!()
617 }
618
619 fn create_navigation(
620 &self,
621 plugins: &mut PluginMap,
622 ) -> Result<Option<Box<dyn Navigation>>, Error> {
623 let (plugin_name, instance) = match &self.navigation {
624 ClientKind::Auto(false) => return Ok(None),
625 ClientKind::Auto(true) => {
626 if self.ros_navigation_client_config.is_some() {
627 return Ok(self.create_navigation_ros());
628 }
629 match PluginConfig::resolve_instance(
630 &self.plugins,
631 None,
632 PluginInstanceKind::Navigation,
633 ) {
634 Err(Error::NoPluginInstance { .. }) => {
635 if self.has_ros_clients() {
640 return Ok(None);
641 }
642 return Ok(Some(self.create_navigation_urdf_viz()));
643 }
644 res => res?,
645 }
646 }
647 ClientKind::Builtin(BuiltinClient::Ros) => {
648 return Ok(self.create_navigation_ros());
649 }
650 ClientKind::Builtin(BuiltinClient::UrdfViz) => {
651 return Ok(Some(self.create_navigation_urdf_viz()));
652 }
653 ClientKind::Plugin(instance_name) => PluginConfig::resolve_instance(
654 &self.plugins,
655 Some(instance_name),
656 PluginInstanceKind::Navigation,
657 )?,
658 };
659
660 Ok(Some(Box::new(instance.create_lazy_instance(
661 plugins,
662 plugin_name,
663 PluginProxy::new_navigation,
664 )?)))
665 }
666
667 fn create_move_base_urdf_viz(&self) -> Box<dyn MoveBase> {
668 let base = arci::Lazy::new(move || {
669 debug!("create_move_base_urdf_viz: creating UrdfVizWebClient");
670 let urdf_viz_client = UrdfVizWebClient::default();
671 urdf_viz_client.run_send_velocity_thread();
672 Ok(urdf_viz_client)
673 });
674 if self.openrr_tracing_config.move_base {
675 Box::new(Tracing::new(base))
676 } else {
677 Box::new(base)
678 }
679 }
680
681 #[cfg(feature = "ros")]
682 fn create_move_base_ros(&self) -> Option<Box<dyn MoveBase>> {
683 let topic = self
684 .ros_cmd_vel_move_base_client_config
685 .as_ref()?
686 .topic
687 .to_string();
688 let base = arci::Lazy::new(move || {
689 debug!("create_move_base_ros: creating RosCmdVelMoveBase");
690 Ok(RosCmdVelMoveBase::new(&topic))
691 });
692 if self.openrr_tracing_config.move_base {
693 Some(Box::new(Tracing::new(base)))
694 } else {
695 Some(Box::new(base))
696 }
697 }
698
699 #[cfg(not(feature = "ros"))]
700 fn create_move_base_ros(&self) -> Option<Box<dyn MoveBase>> {
701 unreachable!()
702 }
703
704 fn create_move_base(
705 &self,
706 plugins: &mut PluginMap,
707 ) -> Result<Option<Box<dyn MoveBase>>, Error> {
708 let (plugin_name, instance) = match &self.move_base {
709 ClientKind::Auto(false) => return Ok(None),
710 ClientKind::Auto(true) => {
711 if self.ros_cmd_vel_move_base_client_config.is_some() {
712 return Ok(self.create_move_base_ros());
713 }
714 match PluginConfig::resolve_instance(
715 &self.plugins,
716 None,
717 PluginInstanceKind::MoveBase,
718 ) {
719 Err(Error::NoPluginInstance { .. }) => {
720 if self.has_ros_clients() {
725 return Ok(None);
726 }
727 return Ok(Some(self.create_move_base_urdf_viz()));
728 }
729 res => res?,
730 }
731 }
732 ClientKind::Builtin(BuiltinClient::Ros) => {
733 return Ok(self.create_move_base_ros());
734 }
735 ClientKind::Builtin(BuiltinClient::UrdfViz) => {
736 return Ok(Some(self.create_move_base_urdf_viz()));
737 }
738 ClientKind::Plugin(instance_name) => PluginConfig::resolve_instance(
739 &self.plugins,
740 Some(instance_name),
741 PluginInstanceKind::MoveBase,
742 )?,
743 };
744
745 Ok(Some(Box::new(instance.create_lazy_instance(
746 plugins,
747 plugin_name,
748 PluginProxy::new_move_base,
749 )?)))
750 }
751
752 fn create_speakers(
753 &self,
754 plugins: &mut PluginMap,
755 ) -> Result<HashMap<String, Arc<dyn Speaker>>, Error> {
756 let mut speakers: HashMap<_, Arc<dyn Speaker>> = HashMap::new();
757 for (name, speak_config) in self
758 .speak_configs
759 .iter()
760 .filter(|(name, _)| self.speakers.as_ref().is_none_or(|v| v.contains(name)))
761 {
762 speakers.insert(name.to_owned(), speak_config.build()?.into());
763 }
764
765 for (plugin_name, config) in &self.plugins {
766 for instance in config.instances.iter().filter(|instance| {
767 instance.type_ == PluginInstanceKind::Speaker
768 && self
769 .speakers
770 .as_ref()
771 .is_none_or(|v| v.contains(&instance.name))
772 }) {
773 if speakers.contains_key(&instance.name) {
774 return Err(Error::DuplicateInstance(format!(
775 "Multiple {:?} instances {:?} are found. Consider renaming one of the instances",
776 instance.type_, instance.name,
777 )));
778 }
779
780 speakers.insert(
781 instance.name.clone(),
782 Arc::new(instance.create_lazy_instance(
783 plugins,
784 plugin_name,
785 PluginProxy::new_speaker,
786 )?),
787 );
788 }
789 }
790
791 if self.speakers.is_none() && speakers.is_empty() {
792 speakers.insert(
793 Self::DEFAULT_SPEAKER_NAME.to_owned(),
794 SpeakConfig::default().build()?.into(),
795 );
796 }
797 Ok(speakers)
798 }
799
800 fn create_raw_joint_trajectory_clients(
801 &self,
802 plugins: &mut PluginMap,
803 ) -> Result<HashMap<String, Arc<dyn JointTrajectoryClient>>, Error> {
804 let is_used = |client_name| {
807 self.joint_trajectory_clients
808 .as_ref()
809 .is_none_or(|v| v.contains(client_name))
810 };
811 let urdf_viz_clients_configs: Vec<_> = self
812 .urdf_viz_clients_configs
813 .iter()
814 .filter(|c| is_used(&c.name))
815 .cloned()
816 .collect();
817 #[cfg(feature = "ros")]
818 let ros_clients_configs: Vec<_> = self
819 .ros_clients_configs
820 .iter()
821 .filter(|c| is_used(&c.name))
822 .collect();
823 #[cfg(feature = "ros")]
824 let ros_action_clients_configs: Vec<_> = self
825 .ros_action_clients_configs
826 .iter()
827 .filter(|c| is_used(&c.name))
828 .collect();
829
830 let mut urdf_robot = None;
831 #[cfg(not(feature = "ros"))]
832 let use_urdf = !urdf_viz_clients_configs.is_empty();
833 #[cfg(feature = "ros")]
834 let use_urdf = !urdf_viz_clients_configs.is_empty()
835 || !ros_clients_configs.is_empty()
836 || !ros_action_clients_configs.is_empty();
837 if use_urdf {
838 if let Some(urdf_path) = self.openrr_clients_config.urdf_full_path() {
839 urdf_robot = Some(urdf_rs::utils::read_urdf_or_xacro(urdf_path)?);
840 }
841 }
842
843 let mut clients = arci_urdf_viz::create_joint_trajectory_clients_lazy(
844 urdf_viz_clients_configs,
845 urdf_robot.as_ref(),
846 )?;
847 #[cfg(feature = "ros")]
848 {
849 clients.extend(arci_ros::create_joint_trajectory_clients_lazy(
850 ros_clients_configs,
851 urdf_robot.as_ref(),
852 )?);
853 clients.extend(arci_ros::create_joint_trajectory_clients_lazy(
854 ros_action_clients_configs,
855 urdf_robot.as_ref(),
856 )?);
857 }
858
859 for (plugin_name, config) in &self.plugins {
860 for instance in config.instances.iter().filter(|instance| {
861 instance.type_ == PluginInstanceKind::JointTrajectoryClient
862 && self
863 .joint_trajectory_clients
864 .as_ref()
865 .is_none_or(|v| v.contains(&instance.name))
866 }) {
867 if clients.contains_key(&instance.name) {
868 return Err(Error::DuplicateInstance(format!(
869 "Multiple {:?} instances {:?} are found. Consider renaming one of the instances",
870 instance.type_, instance.name,
871 )));
872 }
873
874 let client = instance.create_lazy_instance(
875 plugins,
876 plugin_name,
877 PluginProxy::new_joint_trajectory_client,
878 )?;
879 client.get_ref()?;
887 clients.insert(instance.name.clone(), Arc::new(client));
888 }
889 }
890
891 Ok(clients)
892 }
893}
894
895#[allow(clippy::needless_borrows_for_generic_args)] fn resolve_audio_file_path<P: AsRef<Path>>(
898 base_path: P,
899 relative_hash_map: &mut HashMap<String, PathBuf>,
900) -> Result<(), Error> {
901 for v in relative_hash_map.values_mut() {
902 let full_path = openrr_client::resolve_relative_path(base_path.as_ref(), &v)?;
903 *v = full_path;
904 }
905 Ok(())
906}
907
908fn instance_create_error<T: fmt::Debug, U>(
909 res: Result<T, arci::Error>,
910 instance_kind: PluginInstanceKind,
911 instance_name: String,
912 plugin_name: String,
913) -> Result<U, arci::Error> {
914 error!(
915 "failed to create `{instance_kind:?}` instance `{instance_name}` from plugin `{plugin_name}`: {res:?}",
916 );
917 res.and_then(|_| {
918 Err(format_err!(
920 "failed to create `{instance_kind:?}` instance `{instance_name}` from plugin `{plugin_name}`: None",
921 )
922 .into())
923 })
924}
925
926impl RobotConfig {
927 pub fn new<P: AsRef<Path>>(path: P) -> Result<Self, Error> {
928 Self::from_str(
929 &std::fs::read_to_string(&path)
930 .map_err(|e| Error::NoFile(path.as_ref().to_owned(), e))?,
931 &path,
932 )
933 }
934
935 pub fn from_str<P: AsRef<Path>>(s: &str, path: P) -> Result<Self, Error> {
936 let path = path.as_ref();
937
938 let mut config: RobotConfig =
939 toml::from_str(s).map_err(|e| Error::TomlParseFailure(path.to_owned(), e))?;
940
941 config.validate_ros_config()?;
942
943 if config.openrr_clients_config.urdf_path.is_some() {
944 config.openrr_clients_config.resolve_path(path)?;
945 }
946 for speak_config in config.speak_configs.values_mut() {
947 if let SpeakConfig::Audio { map } = speak_config {
948 resolve_audio_file_path(path, map)?;
949 }
950 }
951 for plugin_config in config.plugins.values_mut() {
952 resolve_plugin_path(&mut plugin_config.path, path)?;
953 for instance in &mut plugin_config.instances {
954 if let Some(args_path) = instance.args_from_path.take() {
955 instance.args_from_path =
956 Some(openrr_client::resolve_relative_path(path, args_path)?);
957 }
958 }
959 }
960 debug!("{config:?}");
961 Ok(config)
962 }
963
964 fn validate_ros_config(&self) -> Result<(), Error> {
966 if cfg!(feature = "ros") {
967 return Ok(());
968 }
969
970 for (name, speak_config) in &self.speak_configs {
971 if matches!(speak_config, SpeakConfig::RosEspeak { .. }) {
972 return Err(Error::ConfigRequireRos(format!("speak_configs.{name}")));
973 }
974 }
975 if !self.ros_clients_configs.is_empty() {
976 return Err(Error::ConfigRequireRos("ros_clients_configs".into()));
977 }
978 if !self.ros_action_clients_configs.is_empty() {
979 return Err(Error::ConfigRequireRos("ros_action_clients_configs".into()));
980 }
981 match self.move_base {
982 ClientKind::Builtin(BuiltinClient::Ros) => {
983 return Err(Error::ConfigRequireRos("move_base".into()));
984 }
985 ClientKind::Auto(true) if self.ros_cmd_vel_move_base_client_config.is_some() => {
986 return Err(Error::ConfigRequireRos(
987 "ros_cmd_vel_move_base_client_config".into(),
988 ));
989 }
990 _ => {}
991 }
992 match self.navigation {
993 ClientKind::Builtin(BuiltinClient::Ros) => {
994 return Err(Error::ConfigRequireRos("navigation".into()));
995 }
996 ClientKind::Auto(true) if self.ros_navigation_client_config.is_some() => {
997 return Err(Error::ConfigRequireRos(
998 "ros_navigation_client_config".into(),
999 ));
1000 }
1001 _ => {}
1002 }
1003 match self.localization {
1004 ClientKind::Builtin(BuiltinClient::Ros) => {
1005 return Err(Error::ConfigRequireRos("localization".into()));
1006 }
1007 ClientKind::Auto(true) if self.ros_localization_client_config.is_some() => {
1008 return Err(Error::ConfigRequireRos(
1009 "ros_localization_client_config".into(),
1010 ));
1011 }
1012 _ => {}
1013 }
1014 Ok(())
1015 }
1016}
1017
1018#[cfg(test)]
1019mod test {
1020 use super::*;
1021 #[test]
1022 fn test_resolve_audio_file_path() {
1023 let mut hash = HashMap::new();
1024 hash.insert("a".to_owned(), PathBuf::from("dir1/file.mp3"));
1025 hash.insert("b".to_owned(), PathBuf::from("../dir2/file.mp3"));
1026 resolve_audio_file_path("/config/some_file.toml", &mut hash).unwrap();
1027 assert_eq!(hash.len(), 2);
1028 assert_eq!(hash["a"], PathBuf::from("/config/dir1/file.mp3"));
1029 assert_eq!(hash["b"], PathBuf::from("/config/../dir2/file.mp3"));
1030 }
1031}