1use std::sync::Arc;
3
4use crate::{
5 log::{Log, LogLevel},
6 ros2::Timestamp,
7 Publisher,
8};
9
10pub trait RosoutRaw {
12 fn rosout_writer(&self) -> Arc<Option<Publisher<Log>>>;
14
15 fn base_name(&self) -> &str;
17
18 #[allow(clippy::too_many_arguments)]
20 #[tracing::instrument(skip_all)]
21 fn rosout_raw(
22 &self,
23 timestamp: Timestamp,
24 level: impl Into<LogLevel>,
25 log_name: &str,
26 log_msg: &str,
27 source_file: &str,
28 source_function: &str,
29 source_line: u32,
30 ) {
31 let Some(ref rosout_writer) = *self.rosout_writer() else {
33 tracing::debug!("Tried to log to `rosout`, but it's not turned on. msg: {log_msg}");
34 return;
35 };
36
37 let log_level = Into::<LogLevel>::into(level);
39
40 _ = rosout_writer
42 .publish(Log {
43 timestamp,
44 level: log_level as u8,
45 name: log_name.into(),
46 msg: log_msg.into(),
47 file: source_file.into(),
48 function: source_function.into(),
49 line: source_line,
50 })
51 .inspect_err(|e| tracing::warn!("Failed to publish message to `rosout`! err: {e}"));
52
53 let tracing_msg = format!("[rosout] ({log_name}) {log_msg}");
55 let span = tracing::span!(tracing::Level::ERROR, "rosout_raw");
56 let _guard = span.enter();
57
58 match log_level {
59 LogLevel::Fatal | LogLevel::Error => tracing::error!("{tracing_msg}"),
60 LogLevel::Warn => tracing::warn!("{tracing_msg}"),
61 LogLevel::Info => tracing::info!("{tracing_msg}"),
62 LogLevel::Debug => tracing::debug!("{tracing_msg}"),
63 };
64 }
65}
66
67pub struct NodeLoggingHandle {
69 pub(crate) rosout_writer: Arc<Option<Publisher<Log>>>,
72
73 pub(crate) base_name: String,
75}
76
77impl RosoutRaw for NodeLoggingHandle {
78 fn rosout_writer(&self) -> Arc<Option<Publisher<Log>>> {
79 Arc::clone(&self.rosout_writer)
80 }
81
82 fn base_name(&self) -> &str {
83 &self.base_name
84 }
85}
86
87#[cfg(test)]
88mod tests {
89 use crate::{log::LogLevel, rosout, Context, NodeName};
90
91 mod new_namespace {
92 use crate::{log::LogLevel, rosout, Context, NodeName};
93
94 #[test]
95 fn logging_works_without_import() {
96 let ctx = Context::new().unwrap();
97
98 let node = ctx
99 .new_node(
100 NodeName::new("/", "logging_works_without_import_node").unwrap(),
101 Default::default(),
102 )
103 .unwrap();
104
105 rosout!(node, LogLevel::Warn, "log call works!");
106 }
107
108 #[test]
109 fn logging_handle_works_without_import() {
110 let ctx = Context::new().unwrap();
111
112 let node = ctx
113 .new_node(
114 NodeName::new("/", "logging_works_without_import_node").unwrap(),
115 Default::default(),
116 )
117 .unwrap();
118 let node_logging_handle = node.logging_handle();
119
120 rosout!(node, LogLevel::Warn, "log call works!");
121
122 std::thread::spawn(move || {
123 rosout!(node_logging_handle, LogLevel::Debug, "works here too");
124 })
125 .join()
126 .unwrap();
127 }
128 }
129
130 #[test]
131 fn log_across_threads() {
132 let ctx = Context::new().unwrap();
133
134 let node = ctx
135 .new_node(
136 NodeName::new("/", "log_across_threads_node").unwrap(),
137 Default::default(),
138 )
139 .unwrap();
140
141 let node_logging_handle = node.logging_handle();
143 let handle = std::thread::spawn(move || {
144 for i in 0..50 {
145 rosout!(
146 node_logging_handle,
147 LogLevel::Debug,
148 "hey! system thread on {i}"
149 );
150 }
151 });
152
153 for j in 0..50 {
154 rosout!(node, LogLevel::Debug, "hi! main thread on {j}");
155 }
156
157 handle.join().unwrap();
158 }
159}