openrr_apps/
utils.rs

1use std::{
2    ffi::OsStr,
3    fs, io,
4    path::{Path, PathBuf},
5};
6
7use anyhow::Result;
8use rand::prelude::*;
9use serde::Deserialize;
10use tracing::{debug, warn, Event, Level, Subscriber};
11use tracing_appender::{
12    non_blocking::WorkerGuard,
13    rolling::{RollingFileAppender, Rotation},
14};
15use tracing_subscriber::{
16    fmt::{
17        format::{Format, Writer},
18        FmtContext, FormatEvent, FormatFields, Layer,
19    },
20    layer::SubscriberExt,
21    registry::LookupSpan,
22    EnvFilter,
23};
24
25use crate::{RobotConfig, RobotTeleopConfig};
26
27const OPENRR_APPS_CONFIG_ENV_NAME: &str = "OPENRR_APPS_ROBOT_CONFIG_PATH";
28const DEFAULT_JOINT_CLIENT_NAME: &str = "all";
29
30/// Get robot config from input or env OPENRR_APPS_ROBOT_CONFIG_PATH
31pub fn get_apps_robot_config(config: Option<PathBuf>) -> Option<PathBuf> {
32    if config.is_some() {
33        config
34    } else {
35        std::env::var(OPENRR_APPS_CONFIG_ENV_NAME)
36            .map(|s| {
37                warn!("### ENV VAR {s} is used ###");
38                PathBuf::from(s)
39            })
40            .ok()
41    }
42}
43
44fn evaluate_overwrite_str(doc: &str, scripts: &str, path: Option<&Path>) -> Result<String> {
45    if path.and_then(Path::extension).and_then(OsStr::to_str) == Some("toml") {
46        if let Err(e) = toml::from_str::<toml::Value>(doc) {
47            warn!(
48                "config {} is not valid toml: {}",
49                path.unwrap().display(),
50                e
51            );
52        }
53    }
54    openrr_config::overwrite_str(
55        &openrr_config::evaluate(doc, None)?,
56        &openrr_config::evaluate(scripts, None)?,
57    )
58}
59
60fn evaluate(doc: &str, path: Option<&Path>) -> Result<String> {
61    if path.and_then(Path::extension).and_then(OsStr::to_str) == Some("toml") {
62        if let Err(e) = toml::from_str::<toml::Value>(doc) {
63            warn!(
64                "config {} is not valid toml: {}",
65                path.unwrap().display(),
66                e
67            );
68        }
69    }
70    openrr_config::evaluate(doc, None)
71}
72
73pub fn resolve_robot_config(
74    config_path: Option<&Path>,
75    overwrite: Option<&str>,
76) -> Result<RobotConfig> {
77    match (config_path, overwrite) {
78        (Some(config_path), Some(overwrite)) => {
79            let s = &fs::read_to_string(config_path)?;
80            let s = &evaluate_overwrite_str(s, overwrite, Some(config_path))?;
81            Ok(RobotConfig::from_str(s, config_path)?)
82        }
83        (Some(config_path), None) => {
84            let s = &evaluate(&fs::read_to_string(config_path)?, Some(config_path))?;
85            Ok(RobotConfig::from_str(s, config_path)?)
86        }
87        (None, overwrite) => {
88            let mut config = RobotConfig::default();
89            config
90                .urdf_viz_clients_configs
91                .push(arci_urdf_viz::UrdfVizWebClientConfig {
92                    name: DEFAULT_JOINT_CLIENT_NAME.into(),
93                    joint_names: None,
94                    wrap_with_joint_position_limiter: false,
95                    wrap_with_joint_velocity_limiter: false,
96                    joint_velocity_limits: None,
97                    joint_position_limits: None,
98                });
99            if let Some(overwrite) = overwrite {
100                let s = &toml::to_string(&config)?;
101                let s = &evaluate_overwrite_str(s, overwrite, None)?;
102                config = toml::from_str(s)?;
103            }
104            Ok(config)
105        }
106    }
107}
108
109pub fn resolve_teleop_config(
110    config_path: Option<&Path>,
111    overwrite: Option<&str>,
112) -> Result<RobotTeleopConfig> {
113    match (config_path, overwrite) {
114        (Some(teleop_config_path), Some(overwrite)) => {
115            let s = &fs::read_to_string(teleop_config_path)?;
116            let s = &evaluate_overwrite_str(s, overwrite, Some(teleop_config_path))?;
117            Ok(RobotTeleopConfig::from_str(s, teleop_config_path)?)
118        }
119        (Some(teleop_config_path), None) => {
120            let s = &evaluate(
121                &fs::read_to_string(teleop_config_path)?,
122                Some(teleop_config_path),
123            )?;
124            Ok(RobotTeleopConfig::from_str(s, teleop_config_path)?)
125        }
126        (None, overwrite) => {
127            let mut config = RobotTeleopConfig::default();
128            config.control_modes_config.move_base_mode = Some("base".into());
129            if let Some(overwrite) = overwrite {
130                let s = &toml::to_string(&config)?;
131                let s = &evaluate_overwrite_str(s, overwrite, None)?;
132                config = toml::from_str(s)?;
133            }
134            Ok(config)
135        }
136    }
137}
138
139#[cfg(test)]
140mod test {
141    use super::*;
142    #[test]
143    fn test_get_apps_robot_config() {
144        let path = get_apps_robot_config(Some(PathBuf::from("a.toml")));
145        assert!(path.is_some());
146        assert_eq!(path.unwrap(), PathBuf::from("a.toml"));
147        //
148        std::env::set_var(OPENRR_APPS_CONFIG_ENV_NAME, "b.yaml");
149        let path = get_apps_robot_config(Some(PathBuf::from("a.toml")));
150        assert!(path.is_some());
151        assert_eq!(path.unwrap(), PathBuf::from("a.toml"));
152        std::env::remove_var(OPENRR_APPS_CONFIG_ENV_NAME);
153
154        let path = get_apps_robot_config(None);
155        assert!(path.is_none());
156
157        std::env::set_var(OPENRR_APPS_CONFIG_ENV_NAME, "b.yaml");
158        let path = get_apps_robot_config(None);
159        assert!(path.is_some());
160        assert_eq!(path.unwrap(), PathBuf::from("b.yaml"));
161        std::env::remove_var(OPENRR_APPS_CONFIG_ENV_NAME);
162    }
163    #[test]
164    fn test_log_config_default() {
165        let default = LogConfig::default();
166        assert_eq!(default.level, LogLevel::default());
167        assert_eq!(default.rotation, LogRotation::default());
168        assert_eq!(default.prefix, default_log_prefix());
169    }
170    #[test]
171    fn test_openrr_formatter() {
172        let config = LogConfig {
173            directory: tempfile::tempdir().unwrap().path().to_path_buf(),
174            ..Default::default()
175        };
176        {
177            let _guard = init_tracing_with_file_appender(config.clone(), "prefix".to_string());
178            tracing::info!("log");
179        }
180        assert!(config.directory.is_dir());
181        for entry in std::fs::read_dir(config.directory).unwrap() {
182            let log = std::fs::read_to_string(entry.unwrap().path()).unwrap();
183            assert!(log.starts_with("prefix "));
184        }
185    }
186}
187
188/// Do something needed to start the program
189pub fn init(name: &str, config: &RobotConfig) {
190    #[cfg(feature = "ros")]
191    if config.has_ros_clients() {
192        arci_ros::init(name);
193    }
194    debug!("init {name} with {config:?}");
195}
196
197/// Do something needed to start the program for multiple
198pub fn init_with_anonymize(name: &str, config: &RobotConfig) {
199    let suffix: u64 = rand::thread_rng().gen();
200    let anon_name = format!("{name}_{suffix}");
201    init(&anon_name, config);
202}
203
204pub fn init_tracing() {
205    // TODO: allow enabling both logging
206    // TODO: allow specifying from config
207    if let Some(log_dir) = std::env::var_os("OPENRR_TRACING_DIR") {
208        let file = tracing_appender::rolling::daily(log_dir, "trace");
209        tracing_subscriber::fmt()
210            .json()
211            .with_writer(file)
212            .with_ansi(false)
213            // TODO: only set for openrr-tracing, like openrr_tracing=trace
214            .with_max_level(tracing::Level::TRACE)
215            .with_current_span(false)
216            .init();
217    } else {
218        tracing_subscriber::fmt()
219            .with_env_filter(EnvFilter::from_default_env())
220            .with_writer(io::stderr)
221            .init();
222    }
223}
224
225#[derive(Debug, Clone)]
226pub struct OpenrrFormatter {
227    formatter: Format,
228    name: String,
229}
230
231impl OpenrrFormatter {
232    fn new(name: String) -> Self {
233        Self {
234            formatter: tracing_subscriber::fmt::format(),
235            name,
236        }
237    }
238}
239
240impl<S, N> FormatEvent<S, N> for OpenrrFormatter
241where
242    S: Subscriber + for<'a> LookupSpan<'a>,
243    N: for<'a> FormatFields<'a> + 'static,
244{
245    fn format_event(
246        &self,
247        ctx: &FmtContext<'_, S, N>,
248        mut writer: Writer<'_>,
249        event: &Event<'_>,
250    ) -> std::fmt::Result {
251        write!(writer, "{} ", self.name)?;
252        self.formatter.format_event(ctx, writer, event)
253    }
254}
255
256pub fn init_tracing_with_file_appender(config: LogConfig, name: String) -> WorkerGuard {
257    let default_level = match config.level {
258        LogLevel::TRACE => Level::TRACE,
259        LogLevel::DEBUG => Level::DEBUG,
260        LogLevel::INFO => Level::INFO,
261        LogLevel::WARN => Level::WARN,
262        LogLevel::ERROR => Level::ERROR,
263    };
264    let rotation = match config.rotation {
265        LogRotation::MINUTELY => Rotation::MINUTELY,
266        LogRotation::HOURLY => Rotation::HOURLY,
267        LogRotation::DAILY => Rotation::DAILY,
268        LogRotation::NEVER => Rotation::NEVER,
269    };
270    let formatter = OpenrrFormatter::new(name);
271    let file_appender = RollingFileAppender::new(rotation, config.directory, config.prefix);
272    let (file_writer, guard) = tracing_appender::non_blocking(file_appender);
273    let subscriber = tracing_subscriber::registry()
274        .with(EnvFilter::from_default_env().add_directive(default_level.into()))
275        .with(
276            Layer::new()
277                .event_format(formatter.clone())
278                .with_writer(io::stderr),
279        )
280        .with(
281            Layer::new()
282                .event_format(formatter)
283                .with_writer(file_writer),
284        );
285    tracing::subscriber::set_global_default(subscriber).expect("Unable to set a global collector");
286    guard
287}
288
289#[derive(Deserialize, Debug, Clone, Copy, Default, PartialEq, Eq)]
290pub enum LogLevel {
291    TRACE,
292    DEBUG,
293    #[default]
294    INFO,
295    WARN,
296    ERROR,
297}
298
299#[derive(Deserialize, Debug, Clone, Copy, Default, PartialEq, Eq)]
300pub enum LogRotation {
301    MINUTELY,
302    #[default]
303    HOURLY,
304    DAILY,
305    NEVER,
306}
307
308#[derive(Debug, Deserialize, PartialEq, Clone)]
309pub struct LogConfig {
310    #[serde(default)]
311    pub level: LogLevel,
312    #[serde(default)]
313    pub rotation: LogRotation,
314    #[serde(default = "default_log_directory")]
315    pub directory: PathBuf,
316    #[serde(default = "default_log_prefix")]
317    pub prefix: PathBuf,
318}
319
320impl Default for LogConfig {
321    fn default() -> Self {
322        Self {
323            directory: default_log_directory(),
324            prefix: default_log_prefix(),
325            level: LogLevel::default(),
326            rotation: LogRotation::default(),
327        }
328    }
329}
330
331fn default_log_prefix() -> PathBuf {
332    PathBuf::from("log")
333}
334
335fn default_log_directory() -> PathBuf {
336    std::env::temp_dir()
337}