rosrust_codegen/
msg.rs

1use crate::error::{Result, ResultExt};
2use lazy_static::lazy_static;
3use proc_macro2::{Literal, Span};
4use quote::{quote, ToTokens};
5use ros_message::{DataType, FieldCase, FieldInfo, MessagePath};
6use std::collections::{BTreeSet, HashMap};
7use syn::Ident;
8
9#[derive(Clone, Debug)]
10pub struct Msg(pub ros_message::Msg);
11
12#[derive(Clone, Debug)]
13pub struct Srv {
14    pub path: MessagePath,
15    pub source: String,
16}
17
18impl Msg {
19    pub fn new(path: MessagePath, source: &str) -> Result<Msg> {
20        ros_message::Msg::new(path, source)
21            .map(Self)
22            .chain_err(|| "Failed to parse message")
23    }
24
25    pub fn name_ident(&self) -> Ident {
26        Ident::new(self.0.path().name(), Span::call_site())
27    }
28
29    pub fn token_stream<T: ToTokens>(&self, crate_prefix: &T) -> impl ToTokens {
30        let name = self.name_ident();
31        let fields = self
32            .0
33            .fields()
34            .iter()
35            .map(|v| field_info_field_token_stream(v, crate_prefix))
36            .collect::<Vec<_>>();
37        let field_defaults = self
38            .0
39            .fields()
40            .iter()
41            .map(|v| field_info_field_default_token_stream(v, crate_prefix))
42            .collect::<Vec<_>>();
43        let fields_into_values = self
44            .0
45            .fields()
46            .iter()
47            .map(|v| field_info_field_into_value_token_stream(v, crate_prefix))
48            .collect::<Vec<_>>();
49        let fields_from_values = self
50            .0
51            .fields()
52            .iter()
53            .map(|v| field_info_field_from_value_token_stream(v, crate_prefix))
54            .collect::<Vec<_>>();
55        let fields_for_eq_and_debug = self
56            .0
57            .fields()
58            .iter()
59            .filter_map(|v| field_info_field_name_eq_and_debug_token_stream(v))
60            .collect::<Vec<_>>();
61        let fields_partialeq = fields_for_eq_and_debug
62            .iter()
63            .map(|(_, peq, _)| quote! { self.#peq == other.#peq })
64            .collect::<Vec<_>>();
65        let fields_debug = fields_for_eq_and_debug
66            .iter()
67            .map(|(name, _, dbg)| quote! { .field(stringify!(#name), #dbg) })
68            .collect::<Vec<_>>();
69        let const_fields = self
70            .0
71            .fields()
72            .iter()
73            .map(|v| field_info_const_token_stream(v, crate_prefix))
74            .collect::<Vec<_>>();
75        quote! {
76            #[allow(dead_code, non_camel_case_types, non_snake_case)]
77            #[derive(Clone)]
78            pub struct #name {
79                #(#fields)*
80            }
81
82            impl #name {
83                #(#const_fields)*
84            }
85
86            impl std::convert::From<#name> for #crate_prefix MsgValue {
87                fn from(src: #name) -> Self {
88                    #crate_prefix MsgValue::Message(src.into())
89                }
90            }
91
92            impl std::convert::From<#name> for #crate_prefix MsgMessage {
93                fn from(src: #name) -> Self {
94                    let mut output = Self::new();
95                    #(#fields_into_values)*
96                    output
97                }
98            }
99
100            impl std::convert::TryFrom<#crate_prefix MsgValue> for #name {
101                type Error = ();
102
103                fn try_from(src: #crate_prefix MsgValue) -> Result<Self, ()> {
104                    use std::convert::TryInto;
105                    let message: #crate_prefix MsgMessage = src.try_into()?;
106                    message.try_into()
107                }
108            }
109
110            impl std::convert::TryFrom<#crate_prefix MsgMessage> for #name {
111                type Error = ();
112
113                fn try_from(mut src: #crate_prefix MsgMessage) -> Result<Self, ()> {
114                    use std::convert::TryInto;
115                    Ok(Self {
116                        #(#fields_from_values)*
117                    })
118                }
119            }
120
121            impl std::cmp::PartialEq<Self> for #name {
122                fn eq(&self, other: &Self) -> bool {
123                    true #(&& #fields_partialeq)*
124                }
125            }
126
127            impl std::fmt::Debug for #name {
128                fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
129                    f.debug_struct(stringify!(#name))
130                        #(#fields_debug)*
131                        .finish()
132                }
133            }
134
135            impl Default for #name {
136                fn default() -> Self {
137                    Self {
138                        #(#field_defaults)*
139                    }
140                }
141            }
142        }
143    }
144
145    pub fn token_stream_encode<T: ToTokens>(&self, crate_prefix: &T) -> impl ToTokens {
146        let fields = self
147            .0
148            .fields()
149            .iter()
150            .map(|v| field_info_field_token_stream_encode(v, crate_prefix))
151            .collect::<Vec<_>>();
152        quote! {
153            #(#fields)*
154            Ok(())
155        }
156    }
157
158    pub fn token_stream_decode<T: ToTokens>(&self, crate_prefix: &T) -> impl ToTokens {
159        let fields = self
160            .0
161            .fields()
162            .iter()
163            .map(|v| field_info_field_token_stream_decode(v, crate_prefix))
164            .collect::<Vec<_>>();
165        quote! {
166            Ok(Self {
167                #(#fields)*
168            })
169        }
170    }
171
172    pub fn full_name(&self) -> String {
173        format!("{}", self.0.path())
174    }
175
176    pub fn dependencies(&self) -> Vec<MessagePath> {
177        self.0.dependencies()
178    }
179
180    pub fn get_md5_representation(
181        &self,
182        hashes: &HashMap<MessagePath, String>,
183    ) -> ::std::result::Result<String, ()> {
184        self.0.get_md5_representation(hashes).map_err(|_| ())
185    }
186
187    pub fn has_header(&self) -> bool {
188        self.0.has_header()
189    }
190
191    pub fn header_token_stream<T: ToTokens>(&self, crate_prefix: &T) -> impl ToTokens {
192        if !self.has_header() {
193            return quote! {};
194        }
195        quote! {
196            fn set_header(
197                &mut self,
198                clock: &::std::sync::Arc<#crate_prefix Clock>,
199                seq: &::std::sync::Arc<::std::sync::atomic::AtomicUsize>,
200            ) {
201                if self.header.seq == 0 {
202                    self.header.seq =
203                        seq.fetch_add(1, ::std::sync::atomic::Ordering::SeqCst) as u32;
204                }
205                if self.header.stamp.nanos() == 0 {
206                    self.header.stamp = clock.now();
207                }
208            }
209        }
210    }
211}
212
213lazy_static! {
214    static ref RESERVED_KEYWORDS: BTreeSet<String> = [
215        "as", "break", "const", "continue", "crate", "else", "enum", "extern", "false", "fn",
216        "for", "if", "impl", "in", "let", "loop", "match", "mod", "move", "mut", "pub", "ref",
217        "return", "Self", "self", "static", "struct", "super", "trait", "true", "type", "unsafe",
218        "use", "where", "while", "abstract", "alignof", "become", "box", "do", "final", "macro",
219        "offsetof", "override", "priv", "proc", "pure", "sizeof", "typeof", "unsized", "virtual",
220        "yield",
221    ]
222    .iter()
223    .map(|&item| String::from(item))
224    .collect();
225}
226
227fn field_info_create_identifier(field_info: &FieldInfo, span: Span) -> Ident {
228    if RESERVED_KEYWORDS.contains(field_info.name()) {
229        return Ident::new(&format!("{}_", field_info.name()), span);
230    }
231    Ident::new(field_info.name(), span)
232}
233
234fn field_info_field_token_stream<T: ToTokens>(
235    field_info: &FieldInfo,
236    crate_prefix: &T,
237) -> impl ToTokens {
238    let datatype = datatype_token_stream(field_info.datatype(), crate_prefix);
239    let name = field_info_create_identifier(field_info, Span::call_site());
240    match field_info.case() {
241        FieldCase::Unit => quote! { pub #name: #datatype, },
242        FieldCase::Vector => quote! { pub #name: Vec<#datatype>, },
243        FieldCase::Array(l) => quote! { pub #name: [#datatype; #l], },
244        FieldCase::Const(_) => quote! {},
245    }
246}
247
248fn field_info_field_name_eq_and_debug_token_stream(
249    field_info: &FieldInfo,
250) -> Option<(impl ToTokens, impl ToTokens, impl ToTokens)> {
251    let name = field_info_create_identifier(field_info, Span::call_site());
252    match field_info.case() {
253        FieldCase::Unit | FieldCase::Vector => {
254            Some((quote! { #name }, quote! { #name }, quote! { &self.#name }))
255        }
256        FieldCase::Array(_) => Some((
257            quote! { #name },
258            quote! { #name[..] },
259            quote! { &self.#name.iter().collect::<Vec<_>>() },
260        )),
261        FieldCase::Const(_) => None,
262    }
263}
264
265fn field_info_field_default_token_stream<T: ToTokens>(
266    field_info: &FieldInfo,
267    _crate_prefix: &T,
268) -> impl ToTokens {
269    let name = field_info_create_identifier(field_info, Span::call_site());
270    match field_info.case() {
271        FieldCase::Unit | FieldCase::Vector => quote! { #name: Default::default(), },
272        FieldCase::Array(l) => {
273            let instances = (0..*l).map(|_| quote! {Default::default()});
274            quote! { #name: [#(#instances),*], }
275        }
276        FieldCase::Const(_) => quote! {},
277    }
278}
279
280fn field_info_field_into_value_token_stream<T: ToTokens>(
281    field_info: &FieldInfo,
282    _crate_prefix: &T,
283) -> impl ToTokens {
284    let name = field_info_create_identifier(field_info, Span::call_site());
285    let name_str = field_info.name();
286    match field_info.case() {
287        FieldCase::Unit | FieldCase::Vector | FieldCase::Array(_) => {
288            quote! { output.insert(#name_str.into(), src.#name.into()); }
289        }
290        FieldCase::Const(_) => quote! {},
291    }
292}
293
294fn field_info_field_from_value_token_stream<T: ToTokens>(
295    field_info: &FieldInfo,
296    _crate_prefix: &T,
297) -> impl ToTokens {
298    let name = field_info_create_identifier(field_info, Span::call_site());
299    let name_str = field_info.name();
300    match field_info.case() {
301        FieldCase::Unit | FieldCase::Vector | FieldCase::Array(_) => {
302            quote! { #name: src.remove(#name_str).ok_or(())?.try_into()?, }
303        }
304        FieldCase::Const(_) => quote! {},
305    }
306}
307
308fn field_info_field_token_stream_encode<T: ToTokens>(
309    field_info: &FieldInfo,
310    crate_prefix: &T,
311) -> impl ToTokens {
312    let name = field_info_create_identifier(field_info, Span::call_site());
313    match field_info.case() {
314        FieldCase::Unit => quote! { self.#name.encode(w.by_ref())?; },
315        FieldCase::Vector => match field_info.datatype() {
316            DataType::String
317            | DataType::Time
318            | DataType::Duration
319            | DataType::LocalMessage(_)
320            | DataType::GlobalMessage(_) => {
321                quote! { #crate_prefix rosmsg::encode_variable_slice(&self.#name, w.by_ref())?; }
322            }
323            _ => {
324                quote! { #crate_prefix rosmsg::encode_variable_primitive_slice(&self.#name, w.by_ref())?; }
325            }
326        },
327        FieldCase::Array(_l) => {
328            quote! { #crate_prefix rosmsg::encode_fixed_slice(&self.#name, w.by_ref())?; }
329        }
330        FieldCase::Const(_) => quote! {},
331    }
332}
333
334fn field_info_field_token_stream_decode<T: ToTokens>(
335    field_info: &FieldInfo,
336    crate_prefix: &T,
337) -> impl ToTokens {
338    let name = field_info_create_identifier(field_info, Span::call_site());
339    match field_info.case() {
340        FieldCase::Unit => quote! { #name: #crate_prefix rosmsg::RosMsg::decode(r.by_ref())?, },
341        FieldCase::Vector => match field_info.datatype() {
342            DataType::String
343            | DataType::Time
344            | DataType::Duration
345            | DataType::LocalMessage(_)
346            | DataType::GlobalMessage(_) => {
347                quote! { #name: #crate_prefix rosmsg::decode_variable_vec(r.by_ref())?, }
348            }
349            _ => {
350                quote! { #name: #crate_prefix rosmsg::decode_variable_primitive_vec(r.by_ref())?, }
351            }
352        },
353        FieldCase::Array(l) => {
354            let lines =
355                (0..*l).map(|_| quote! { #crate_prefix rosmsg::RosMsg::decode(r.by_ref())?, });
356            quote! { #name: [#(#lines)*], }
357        }
358        FieldCase::Const(_) => quote! {},
359    }
360}
361
362fn field_info_const_token_stream<T: ToTokens>(
363    field_info: &FieldInfo,
364    crate_prefix: &T,
365) -> impl ToTokens {
366    let value = match field_info.case() {
367        FieldCase::Const(ref value) => value,
368        _ => return quote! {},
369    };
370    let name = field_info_create_identifier(field_info, Span::call_site());
371    let datatype = datatype_token_stream(field_info.datatype(), crate_prefix);
372    let insides = match field_info.datatype() {
373        DataType::Bool => {
374            let bool_value = if value != "0" {
375                quote! { true }
376            } else {
377                quote! { false }
378            };
379            quote! { #name: bool = #bool_value }
380        }
381        DataType::String => quote! { #name: &'static str = #value },
382        DataType::Time
383        | DataType::Duration
384        | DataType::LocalMessage(..)
385        | DataType::GlobalMessage(..) => return quote! {},
386        DataType::I8(_) => {
387            let numeric_value = Literal::i8_suffixed(value.parse().unwrap());
388            quote! { #name: #datatype = #numeric_value as #datatype }
389        }
390        DataType::I16 => {
391            let numeric_value = Literal::i16_suffixed(value.parse().unwrap());
392            quote! { #name: #datatype = #numeric_value as #datatype }
393        }
394        DataType::I32 => {
395            let numeric_value = Literal::i32_suffixed(value.parse().unwrap());
396            quote! { #name: #datatype = #numeric_value as #datatype }
397        }
398        DataType::I64 => {
399            let numeric_value = Literal::i64_suffixed(value.parse().unwrap());
400            quote! { #name: #datatype = #numeric_value as #datatype }
401        }
402        DataType::U8(_) => {
403            let numeric_value = Literal::u8_suffixed(value.parse().unwrap());
404            quote! { #name: #datatype = #numeric_value as #datatype }
405        }
406        DataType::U16 => {
407            let numeric_value = Literal::u16_suffixed(value.parse().unwrap());
408            quote! { #name: #datatype = #numeric_value as #datatype }
409        }
410        DataType::U32 => {
411            let numeric_value = Literal::u32_suffixed(value.parse().unwrap());
412            quote! { #name: #datatype = #numeric_value as #datatype }
413        }
414        DataType::U64 => {
415            let numeric_value = Literal::u64_suffixed(value.parse().unwrap());
416            quote! { #name: #datatype = #numeric_value as #datatype }
417        }
418        DataType::F32 => {
419            let numeric_value = Literal::f32_suffixed(value.parse().unwrap());
420            quote! { #name: #datatype = #numeric_value as #datatype }
421        }
422        DataType::F64 => {
423            let numeric_value = Literal::f64_suffixed(value.parse().unwrap());
424            quote! { #name: #datatype = #numeric_value as #datatype }
425        }
426    };
427    quote! {
428        #[allow(dead_code,non_upper_case_globals)]
429        pub const #insides;
430    }
431}
432
433fn datatype_token_stream<T: ToTokens>(data_type: &DataType, crate_prefix: &T) -> impl ToTokens {
434    match data_type {
435        DataType::Bool => quote! { bool },
436        DataType::I8(_) => quote! { i8 },
437        DataType::I16 => quote! { i16 },
438        DataType::I32 => quote! { i32 },
439        DataType::I64 => quote! { i64 },
440        DataType::U8(_) => quote! { u8 },
441        DataType::U16 => quote! { u16 },
442        DataType::U32 => quote! { u32 },
443        DataType::U64 => quote! { u64 },
444        DataType::F32 => quote! { f32 },
445        DataType::F64 => quote! { f64 },
446        DataType::String => quote! { ::std::string::String },
447        DataType::Time => quote! { #crate_prefix Time },
448        DataType::Duration => quote! { #crate_prefix Duration },
449        DataType::LocalMessage(ref name) => {
450            let name = Ident::new(name, Span::call_site());
451            quote! { #name }
452        }
453        DataType::GlobalMessage(ref message) => {
454            let name = Ident::new(message.name(), Span::call_site());
455            let pkg = Ident::new(message.package(), Span::call_site());
456            quote! { super::#pkg::#name }
457        }
458    }
459}