libits_client/reception/exchange/
mod.rs

1// Software Name: its-client
2// SPDX-FileCopyrightText: Copyright (c) 2016-2022 Orange
3// SPDX-License-Identifier: MIT License
4//
5// This software is distributed under the MIT license, see LICENSE.txt file for more details.
6//
7// Author: Frédéric GARDES <frederic.gardes@orange.com> et al.
8// Software description: This Intelligent Transportation Systems (ITS) [MQTT](https://mqtt.org/) client based on the [JSon](https://www.json.org) [ETSI](https://www.etsi.org/committee/its) specification transcription provides a ready to connect project for the mobility (connected and autonomous vehicles, road side units, vulnerable road users,...).
9use std::{cmp, hash};
10
11use serde::{Deserialize, Serialize};
12
13use crate::analyse::configuration::Configuration;
14use crate::reception::exchange::message::Message;
15use crate::reception::exchange::reference_position::ReferencePosition;
16use crate::reception::mortal::{now, Mortal};
17use crate::reception::Reception;
18
19pub mod collective_perception_message;
20pub mod cooperative_awareness_message;
21pub mod decentralized_environmental_notification_message;
22pub mod message;
23pub mod mobile;
24pub mod mobile_perceived_object;
25pub mod perceived_object;
26pub mod reference_position;
27
28#[serde_with::skip_serializing_none]
29#[derive(Clone, Debug, Serialize, Deserialize)]
30pub struct Exchange {
31    #[serde(rename = "type")]
32    pub type_field: String,
33    pub origin: String,
34    pub version: String,
35    pub source_uuid: String,
36    pub timestamp: u128,
37    #[serde(skip_serializing_if = "Vec::is_empty", default)]
38    pub path: Vec<PathElement>,
39    pub message: Message,
40}
41
42#[serde_with::skip_serializing_none]
43#[derive(Debug, Clone, Hash, PartialEq, Serialize, Deserialize)]
44pub struct PathElement {
45    pub mobile_id: u32,
46    pub position: ReferencePosition,
47    pub message_type: String,
48}
49
50#[serde_with::skip_serializing_none]
51#[derive(Default, Debug, Clone, Hash, PartialEq, Serialize, Deserialize)]
52pub struct PositionConfidence {
53    pub position_confidence_ellipse: Option<PositionConfidenceEllipse>,
54    pub altitude: Option<u8>,
55}
56
57#[serde_with::skip_serializing_none]
58#[derive(Default, Debug, Clone, Hash, PartialEq, Serialize, Deserialize)]
59pub struct PositionConfidenceEllipse {
60    pub semi_major_confidence: Option<u16>,
61    pub semi_minor_confidence: Option<u16>,
62    pub semi_major_orientation: Option<u16>,
63}
64
65#[serde_with::skip_serializing_none]
66#[derive(Default, Debug, Clone, Hash, PartialEq, Serialize, Deserialize)]
67pub struct PathHistory {
68    pub path_position: PathPosition,
69    pub path_delta_time: Option<u16>,
70}
71
72#[serde_with::skip_serializing_none]
73#[derive(Default, Debug, Clone, Hash, PartialEq, Serialize, Deserialize)]
74pub struct PathPosition {
75    pub delta_latitude: Option<i32>,
76    pub delta_longitude: Option<i32>,
77    pub delta_altitude: Option<i32>,
78}
79
80impl Exchange {
81    pub fn new(
82        component: String,
83        timestamp: u128,
84        path: Vec<PathElement>,
85        message: Message,
86    ) -> Box<Exchange> {
87        Box::from(Exchange {
88            type_field: message.get_type(),
89            origin: "mec_application".to_string(),
90            version: "1.1.1".to_string(),
91            source_uuid: component,
92            path,
93            timestamp,
94            message,
95        })
96    }
97
98    // TODO find a better way to appropriate
99    pub fn appropriate(&mut self, configuration: &Configuration, timestamp: u128) {
100        self.origin = "mec_application".to_string();
101        let _number = self.message.appropriate(configuration, timestamp);
102        self.source_uuid = configuration.component_name(None);
103        self.timestamp = timestamp;
104    }
105}
106
107impl Mortal for Exchange {
108    fn timeout(&self) -> u128 {
109        self.message.timeout()
110    }
111
112    fn terminate(&mut self) {
113        self.message.terminate();
114    }
115
116    fn terminated(&self) -> bool {
117        self.message.terminated()
118    }
119
120    fn remaining_time(&self) -> u128 {
121        return (self.timeout() - now()) / 1000;
122    }
123}
124
125impl Reception for Exchange {}
126
127impl hash::Hash for Exchange {
128    fn hash<H: hash::Hasher>(&self, state: &mut H) {
129        self.message.hash(state);
130    }
131}
132
133impl cmp::PartialEq for Exchange {
134    fn eq(&self, other: &Self) -> bool {
135        self.message == other.message
136    }
137}
138
139impl cmp::Eq for Exchange {}
140
141#[cfg(test)]
142mod tests {
143    use crate::reception::exchange::message::Message;
144    use crate::reception::exchange::Exchange;
145
146    fn basic_cam() -> &'static str {
147        return r#"
148{
149  "type": "cam",
150  "origin": "self",
151  "version": "1.0.0",
152  "source_uuid": "uuid14",
153  "timestamp": 1574778515424,
154  "message": {
155    "protocol_version": 1,
156    "station_id": 42,
157    "generation_delta_time": 3,
158    "basic_container": {
159      "reference_position": {
160        "latitude": 486263556,
161        "longitude": 22492123,
162        "altitude": 20000
163      }
164    },
165    "high_frequency_container": {}
166  }
167}
168"#;
169    }
170
171    fn standard_cam() -> &'static str {
172        return r#"
173{
174  "type": "cam",
175  "origin": "self",
176  "version": "1.0.0",
177  "source_uuid": "uuid14",
178  "timestamp": 1574778515424,
179  "message": {
180    "protocol_version": 1,
181    "station_id": 42,
182    "generation_delta_time": 3,
183    "basic_container": {
184      "station_type": 5,
185      "reference_position": {
186        "latitude": 486263556,
187        "longitude": 22492123,
188        "altitude": 20000
189      },
190      "confidence": {
191        "position_confidence_ellipse": {
192          "semi_major_confidence": 100,
193          "semi_minor_confidence": 50,
194          "semi_major_orientation": 180
195        },
196        "altitude": 3
197      }
198    },
199    "high_frequency_container": {
200      "heading": 180,
201      "speed": 365,
202      "drive_direction": 0,
203      "vehicle_length": 40,
204      "vehicle_width": 20,
205      "confidence": {
206        "heading": 2,
207        "speed": 3,
208        "vehicle_length": 0
209      }
210    }
211  }
212}
213"#;
214    }
215
216    fn full_cam() -> &'static str {
217        return r#"
218{
219  "type": "cam",
220  "origin": "self",
221  "version": "1.0.0",
222  "source_uuid": "uuid14",
223  "timestamp": 1574778515424,
224  "message": {
225    "protocol_version": 1,
226    "station_id": 42,
227    "generation_delta_time": 3,
228    "basic_container": {
229      "station_type": 5,
230      "reference_position": {
231        "latitude": 486263556,
232        "longitude": 22492123,
233        "altitude": 20000
234      },
235      "confidence": {
236        "position_confidence_ellipse": {
237          "semi_major_confidence": 100,
238          "semi_minor_confidence": 50,
239          "semi_major_orientation": 180
240        },
241        "altitude": 3
242      }
243    },
244    "high_frequency_container": {
245      "heading": 180,
246      "speed": 253,
247      "drive_direction": 0,
248      "vehicle_length": 40,
249      "vehicle_width": 20,
250      "curvature": 0,
251      "curvature_calculation_mode": 1,
252      "longitudinal_acceleration": 2,
253      "yaw_rate": 0,
254      "acceleration_control": "0000010",
255      "lane_position": 1,
256      "lateral_acceleration": 7,
257      "vertical_acceleration": 2,
258      "confidence": {
259        "heading": 2,
260        "speed": 3,
261        "vehicle_length": 0,
262        "yaw_rate": 0,
263        "longitudinal_acceleration": 1,
264        "curvature": 1,
265        "lateral_acceleration": 2,
266        "vertical_acceleration": 1
267      }
268    },
269    "low_frequency_container": {
270      "vehicle_role": 0,
271      "exterior_lights": "00000011",
272      "path_history": [
273        {
274          "path_position": {
275            "delta_latitude": 102,
276            "delta_longitude": 58,
277            "delta_altitude": -10
278          },
279          "path_delta_time": 19
280        },
281        {
282          "path_position": {
283            "delta_latitude": 96,
284            "delta_longitude": 42,
285            "delta_altitude": -6
286          },
287          "path_delta_time": 21
288        }
289      ]
290    }
291  }
292}
293"#;
294    }
295
296    fn basic_denm() -> &'static str {
297        return r#"
298{
299  "type": "denm",
300  "origin": "self",
301  "version": "1.0.0",
302  "source_uuid": "uuid14",
303  "timestamp": 1574778515425,
304  "message": {
305    "protocol_version": 1,
306    "station_id": 42,
307    "management_container": {
308      "action_id": {
309        "originating_station_id": 41,
310        "sequence_number": 1
311      },
312      "detection_time": 503253331000,
313      "reference_time": 503253331050,
314      "event_position": {
315        "latitude": 486263556,
316        "longitude": 224921234,
317        "altitude": 20000
318      }
319    }
320  }
321}
322    "#;
323    }
324
325    fn standard_denm() -> &'static str {
326        return r#"
327{
328  "type": "denm",
329  "origin": "self",
330  "version": "1.0.0",
331  "source_uuid": "uuid14",
332  "timestamp": 1574778515425,
333  "message": {
334    "protocol_version": 1,
335    "station_id": 42,
336    "management_container": {
337      "action_id": {
338        "originating_station_id": 41,
339        "sequence_number": 1
340      },
341      "detection_time": 503253332000,
342      "reference_time": 503253330000,
343      "event_position": {
344        "latitude": 486263556,
345        "longitude": 224921234,
346        "altitude": 20000
347      },
348      "station_type": 5,
349      "confidence": {
350        "position_confidence_ellipse": {
351          "semi_major_confidence": 100,
352          "semi_minor_confidence": 50,
353          "semi_major_orientation": 180
354        },
355        "altitude": 3
356      }
357    },
358    "situation_container": {
359      "event_type": {
360        "cause": 97,
361        "subcause": 0
362      }
363    },
364    "location_container": {
365      "event_speed": 289,
366      "event_position_heading": 1806,
367      "traces": [
368        {
369          "path_history": []
370        }
371      ],
372      "confidence": {
373        "speed": 3,
374        "heading": 2
375      }
376    }
377  }
378}
379    "#;
380    }
381
382    fn full_denm() -> &'static str {
383        return r#"
384{
385  "type": "denm",
386  "origin": "self",
387  "version": "1.0.0",
388  "source_uuid": "uuid14",
389  "timestamp": 1574778515425,
390  "message": {
391    "protocol_version": 1,
392    "station_id": 42,
393    "management_container": {
394      "action_id": {
395        "originating_station_id": 41,
396        "sequence_number": 1
397      },
398      "detection_time": 503253332000,
399      "reference_time": 503253330000,
400      "termination": 1,
401      "event_position": {
402        "latitude": 486263556,
403        "longitude": 224921234,
404        "altitude": 20000
405      },
406      "relevance_distance": 3,
407      "relevance_traffic_direction": 2,
408      "validity_duration": 600,
409      "transmission_interval": 500,
410      "station_type": 5,
411      "confidence": {
412        "position_confidence_ellipse": {
413          "semi_major_confidence": 100,
414          "semi_minor_confidence": 50,
415          "semi_major_orientation": 180
416        },
417        "altitude": 3
418      }
419    },
420    "situation_container": {
421      "information_quality": 1,
422      "event_type": {
423        "cause": 97,
424        "subcause": 0
425      },
426      "linked_cause": {
427        "cause": 1,
428        "subcause": 1
429      }
430    },
431    "location_container": {
432      "event_speed": 289,
433      "event_position_heading": 1806,
434      "traces": [
435        {
436          "path_history": [
437            {
438              "path_position": {
439                "delta_latitude": 102,
440                "delta_longitude": 58,
441                "delta_altitude": -10
442              },
443              "path_delta_time": 19
444            },
445            {
446              "path_position": {
447                "delta_latitude": 96,
448                "delta_longitude": 42,
449                "delta_altitude": -6
450              },
451              "path_delta_time": 21
452            }
453          ]
454        },
455        {
456          "path_history": [
457            {
458              "path_position": {
459                "delta_latitude": 75,
460                "delta_longitude": 12,
461                "delta_altitude": 3
462              },
463              "path_delta_time": 20
464            },
465            {
466              "path_position": {
467                "delta_latitude": 74,
468                "delta_longitude": 11,
469                "delta_altitude": 2
470              },
471              "path_delta_time": 20
472            },
473            {
474              "path_position": {
475                "delta_latitude": 73,
476                "delta_longitude": 10,
477                "delta_altitude": 6
478              },
479              "path_delta_time": 20
480            }
481          ]
482        }
483      ],
484      "road_type": 0,
485      "confidence": {
486        "speed": 3,
487        "heading": 2
488      }
489    },
490    "alacarte_container": {
491      "lane_position": -1,
492      "positioning_solution": 2
493    }
494  }
495}
496    "#;
497    }
498
499    fn basic_cpm() -> &'static str {
500        return r#"{
501          "type": "cpm",
502          "origin": "self",
503          "version": "1.1.3",
504          "source_uuid": "uuid1",
505          "timestamp": 1574778515425,
506          "message": {
507            "protocol_version": 1,
508            "station_id": 12345,
509            "generation_delta_time": 65535,
510            "management_container": {
511              "station_type": 5,
512              "reference_position": {
513                "latitude": 426263556,
514                "longitude": -82492123,
515                "altitude": 800001
516              },
517              "confidence": {
518                "position_confidence_ellipse": {
519                  "semi_major_confidence": 4095,
520                  "semi_minor_confidence": 4095,
521                  "semi_major_orientation": 3601
522                },
523                "altitude": 15
524              }
525            }
526          }
527        }"#;
528    }
529
530    fn standard_cpm() -> &'static str {
531        return r#"{
532            "type": "cpm",
533            "origin": "self",
534            "version": "1.1.3",
535            "source_uuid": "uuid1",
536            "timestamp": 1574778515425,
537            "message": {
538                "protocol_version": 1,
539                "station_id": 12345,
540                "generation_delta_time": 65535,
541                "management_container": {
542                    "station_type": 5,
543                    "reference_position": {
544                        "latitude": 426263556,
545                        "longitude": -82492123,
546                        "altitude": 800001
547                    },
548                    "confidence": {
549                        "position_confidence_ellipse": {
550                            "semi_major_confidence": 4095,
551                            "semi_minor_confidence": 4095,
552                            "semi_major_orientation": 3601
553                        },
554                        "altitude": 15
555                    }
556                },
557                "station_data_container": {
558                    "originating_vehicle_container": {
559                        "heading": 180,
560                        "speed": 1600,
561                        "confidence": {
562                            "heading": 127,
563                            "speed": 127
564                        }
565                    }
566                },
567                "sensor_information_container": [{
568                    "sensor_id": 1,
569                    "type": 3,
570                    "detection_area": {
571                        "vehicle_sensor": {
572                            "ref_point_id": 0,
573                            "x_sensor_offset": -20,
574                            "y_sensor_offset": 20,
575                            "vehicle_sensor_property_list": [{
576                                "range": 5000,
577                                "horizontal_opening_angle_start": 600,
578                                "horizontal_opening_angle_end": 600
579                            }]
580                        }
581                    }
582                }],
583                "perceived_object_container": [{
584                    "object_id": 0,
585                    "time_of_measurement": 50,
586                    "confidence": {
587                        "x_distance": 102,
588                        "y_distance": 102,
589                        "x_speed": 127,
590                        "y_speed": 127,
591                        "object": 10
592                    },
593                    "x_distance": 400,
594                    "y_distance": 100,
595                    "x_speed": 1400,
596                    "y_speed": 500,
597                    "object_age": 1500
598                }]
599            }
600        }"#;
601    }
602
603    fn full_cpm() -> &'static str {
604        return r#"{
605            "type": "cpm",
606            "origin": "self",
607            "version": "1.1.3",
608            "source_uuid": "uuid1",
609            "timestamp": 1574778515425,
610            "message": {
611                "protocol_version": 255,
612                "station_id": 4294967295,
613                "generation_delta_time": 65535,
614                "management_container": {
615                    "station_type": 254,
616                    "reference_position": {
617                        "latitude": 426263556,
618                        "longitude": -82492123,
619                        "altitude": 800001
620                    },
621                    "confidence": {
622                        "position_confidence_ellipse": {
623                            "semi_major_confidence": 4095,
624                            "semi_minor_confidence": 4095,
625                            "semi_major_orientation": 3601
626                        },
627                        "altitude": 15
628                    }
629                },
630                "station_data_container": {
631                    "originating_vehicle_container": {
632                        "heading": 180,
633                        "speed": 1600,
634                        "drive_direction": 0,
635                        "vehicle_length": 31,
636                        "vehicle_width": 18,
637                        "longitudinal_acceleration": -160,
638                        "yaw_rate": -32766,
639                        "lateral_acceleration": -2,
640                        "vertical_acceleration": -1,
641                        "confidence": {
642                            "heading": 127,
643                            "speed": 127,
644                            "vehicle_length": 3,
645                            "yaw_rate": 2,
646                            "longitudinal_acceleration": 12,
647                            "lateral_acceleration": 13,
648                            "vertical_acceleration": 14
649                        }
650                    }
651                },
652                "sensor_information_container": [{
653                    "sensor_id": 1,
654                    "type": 3,
655                    "detection_area": {
656                        "vehicle_sensor": {
657                            "ref_point_id": 255,
658                            "x_sensor_offset": -3094,
659                            "y_sensor_offset": -1000,
660                            "z_sensor_offset": 1000,
661                            "vehicle_sensor_property_list": [{
662                                "range": 10000,
663                                "horizontal_opening_angle_start": 3601,
664                                "horizontal_opening_angle_end": 3601,
665                                "vertical_opening_angle_start": 3601,
666                                "vertical_opening_angle_end": 3601
667                            }]
668                        }
669                    }
670                }],
671                "perceived_object_container": [{
672                    "object_id": 0,
673                    "time_of_measurement": 50,
674                    "confidence": {
675                        "x_distance": 102,
676                        "y_distance": 102,
677                        "x_speed": 7,
678                        "y_speed": 7,
679                        "object": 10
680                    },
681                    "x_distance": 400,
682                    "y_distance": 100,
683                    "z_distance": 50,
684                    "x_speed": 1400,
685                    "y_speed": 500,
686                    "z_speed": 0,
687                    "object_age": 1500,
688                    "object_ref_point": 8,
689                    "x_acceleration": -160,
690                    "y_acceleration": 0,
691                    "z_acceleration": 161,
692                    "roll_angle": 0,
693                    "pitch_angle": 3600,
694                    "yaw_angle": 3601,
695                    "roll_rate": -32766,
696                    "pitch_rate": 0,
697                    "yaw_rate": 32767,
698                    "roll_acceleration": -32766,
699                    "pitch_acceleration": 0,
700                    "yaw_acceleration": 32767,
701                    "lower_triangular_correlation_matrix_columns": [
702                        [-100, -99, -98],
703                        [0, 1, 2],
704                        [98, 99, 100]
705                    ],
706                    "planar_object_dimension_1": 1023,
707                    "planar_object_dimension_2": 1023,
708                    "vertical_object_dimension": 1023,
709                    "sensor_id_list": [1, 2, 10, 100, 255],
710                    "dynamic_status": 2,
711                    "classification": [{
712                        "object_class": {
713                            "vehicle": 10
714                        },
715                        "confidence": 101
716                    }, {
717                        "object_class": {
718                            "single_vru": {
719                                "pedestrian": 2
720                            }
721                        },
722                        "confidence": 25
723                    }, {
724                        "object_class": {
725                            "vru_group": {
726                                "group_size": 12,
727                                "group_type": {
728                                    "pedestrian": true,
729                                    "bicyclist": false,
730                                    "motorcyclist": false,
731                                    "animal": true
732                                },
733                                "cluster_id": 255
734                            }
735                        },
736                        "confidence": 64
737                    }, {
738                        "object_class": {
739                            "other": 1
740                        },
741                        "confidence": 0
742                    }],
743                    "matched_position": {
744                        "lane_id": 255,
745                        "longitudinal_lane_position": 32767
746                    }
747                }]
748            }
749        }"#;
750    }
751
752    fn bad_cam_without_timestamp() -> &'static str {
753        return r#"
754{
755  "type": "cam",
756  "origin": "self",
757  "version": "1.0.0",
758  "source_uuid": "uuid14",
759  "message": {
760    "protocol_version": 1,
761    "station_id": 42,
762    "generation_delta_time": 3,
763    "basic_container": {
764      "reference_position": {
765        "latitude": 486263556,
766        "longitude": 22492123,
767        "altitude": 20000
768      }
769    },
770    "high_frequency_container": {}
771  }
772}
773"#;
774    }
775
776    fn bad_denm_with_string_timestamp() -> &'static str {
777        return r#"
778{
779  "type": "denm",
780  "origin": "self",
781  "version": "1.0.0",
782  "source_uuid": "uuid14",
783  "timestamp": "1574778515425",
784  "message": {
785    "protocol_version": 1,
786    "station_id": 42,
787    "management_container": {
788      "action_id": {
789        "originating_station_id": 41,
790        "sequence_number": 1
791      },
792      "detection_time": 503253332000,
793      "reference_time": 503253330000,
794      "event_position": {
795        "latitude": 486263556,
796        "longitude": 224921234,
797        "altitude": 20000
798      }
799    }
800  }
801}
802    "#;
803    }
804
805    fn bad_denm_with_protocol_version_u32() -> &'static str {
806        return r#"
807{
808  "type": "denm",
809  "origin": "self",
810  "version": "1.0.0",
811  "source_uuid": "uuid14",
812  "timestamp": 1574778515425,
813  "message": {
814    "protocol_version": 4242424242,
815    "station_id": 42,
816    "management_container": {
817      "action_id": {
818        "originating_station_id": 41,
819        "sequence_number": 1
820      },
821      "detection_time": 503253332000,
822      "reference_time": 503253330000,
823      "event_position": {
824        "latitude": 486263556,
825        "longitude": 224921234,
826        "altitude": 20000
827      }
828    }
829  }
830}
831    "#;
832    }
833
834    fn bad_cpm_with_negative_timestamp() -> &'static str {
835        return r#"
836{
837  "type": "cpm",
838  "origin": "self",
839  "version": "1.0.0",
840  "source_uuid": "uuid1",
841  "timestamp": -1,
842  "message": {
843    "protocol_version": 1,
844    "station_id": 12345,
845    "message_id": 14,
846    "generation_delta_time": 65535,
847    "management_container": {
848      "station_type": 5,
849      "reference_position": {
850        "latitude": 426263556,
851        "longitude": -82492123,
852        "altitude": 800001
853      },
854      "confidence": {
855        "position_confidence_ellipse": {
856          "semi_major_confidence": 4095,
857          "semi_minor_confidence": 4095,
858          "semi_major_orientation": 3601
859        },
860        "altitude": 15
861      }
862    },
863    "numberOfPerceivedObjects": 1
864  }
865}"#;
866    }
867
868    fn remove_whitespace(s: &str) -> String {
869        s.split_whitespace().collect()
870    }
871
872    #[test]
873    fn it_can_deserialize_then_serialize_a_basic_cam() {
874        let json = basic_cam();
875        let cam: Exchange = serde_json::from_str(json).unwrap();
876        assert_eq!(cam.timestamp, 1574778515424);
877        assert_eq!(
878            serde_json::to_string(&cam).unwrap(),
879            remove_whitespace(json)
880        );
881    }
882
883    #[test]
884    fn it_can_deserialize_then_serialize_a_standard_cam() {
885        let json = standard_cam();
886        let cam: Exchange = serde_json::from_str(json).unwrap();
887        assert_eq!(cam.timestamp, 1574778515424);
888        if let Message::CAM(message) = &cam.message {
889            assert_eq!(message.high_frequency_container.speed.unwrap(), 365);
890            assert_eq!(
891                serde_json::to_string(&cam).unwrap(),
892                remove_whitespace(json)
893            );
894        } else {
895            panic!("no cam deserialized");
896        };
897    }
898
899    #[test]
900    fn it_can_deserialize_then_serialize_a_full_cam() {
901        let json = full_cam();
902        let cam: Exchange = serde_json::from_str(json).unwrap();
903        assert_eq!(cam.timestamp, 1574778515424);
904        if let Message::CAM(message) = &cam.message {
905            assert_eq!(message.high_frequency_container.speed.unwrap(), 253);
906            assert_eq!(
907                message
908                    .high_frequency_container
909                    .curvature_calculation_mode
910                    .unwrap(),
911                1
912            );
913            assert_eq!(
914                serde_json::to_string(&cam).unwrap(),
915                remove_whitespace(json)
916            );
917        } else {
918            panic!("no cam deserialized");
919        };
920    }
921
922    #[test]
923    fn it_can_deserialize_then_serialize_a_basic_denm() {
924        let json = basic_denm();
925        let denm: Exchange = serde_json::from_str(json).unwrap();
926        assert_eq!(denm.timestamp, 1574778515425);
927        if let Message::DENM(message) = &denm.message {
928            assert_eq!(
929                message
930                    .management_container
931                    .action_id
932                    .originating_station_id,
933                41
934            );
935            assert_eq!(
936                serde_json::to_string(&denm).unwrap(),
937                remove_whitespace(json)
938            );
939        } else {
940            panic!("no denm deserialized");
941        };
942    }
943
944    #[test]
945    fn it_can_deserialize_then_serialize_a_standard_denm() {
946        let json = standard_denm();
947        let denm: Exchange = serde_json::from_str(json).unwrap();
948        assert_eq!(denm.timestamp, 1574778515425);
949        if let Message::DENM(message) = &denm.message {
950            assert_eq!(
951                message
952                    .management_container
953                    .action_id
954                    .originating_station_id,
955                41
956            );
957            match &message.situation_container {
958                Some(s) => assert_eq!(s.event_type.cause, 97),
959                None => panic!("Situation container is undefined"),
960            };
961            assert_eq!(
962                serde_json::to_string(&denm).unwrap(),
963                remove_whitespace(json)
964            );
965        } else {
966            panic!("no denm deserialized");
967        };
968    }
969
970    #[test]
971    fn it_can_deserialize_then_serialize_a_full_denm() {
972        let json = full_denm();
973        let denm: Exchange = serde_json::from_str(json).unwrap();
974        assert_eq!(denm.timestamp, 1574778515425);
975        if let Message::DENM(message) = &denm.message {
976            assert_eq!(
977                message
978                    .management_container
979                    .action_id
980                    .originating_station_id,
981                41
982            );
983            match &message.situation_container {
984                Some(s) => {
985                    assert_eq!(s.event_type.cause, 97);
986                    assert_eq!(s.information_quality.unwrap(), 1);
987                    match &s.linked_cause {
988                        Some(lc) => assert_eq!(lc.cause, 1),
989                        None => panic!("Linked cause is undefined"),
990                    };
991                }
992                None => panic!("Situation container is undefined"),
993            };
994            assert_eq!(
995                serde_json::to_string(&denm).unwrap(),
996                remove_whitespace(json)
997            );
998        } else {
999            panic!("no denm deserialized");
1000        };
1001    }
1002
1003    #[test]
1004    fn it_can_deserialize_then_serialize_a_basic_cpm() {
1005        let json = basic_cpm();
1006        let cpm: Exchange = serde_json::from_str(json).unwrap();
1007        assert_eq!(cpm.timestamp, 1574778515425);
1008        assert_eq!(
1009            serde_json::to_string(&cpm).unwrap(),
1010            remove_whitespace(json)
1011        );
1012    }
1013
1014    #[test]
1015    fn it_can_deserialize_then_serialize_a_standard_cpm() {
1016        let json = standard_cpm();
1017        let cpm: Exchange = serde_json::from_str(json).unwrap();
1018        assert_eq!(cpm.timestamp, 1574778515425);
1019        if let Message::CPM(message) = &cpm.message {
1020            assert_eq!(
1021                message
1022                    .station_data_container
1023                    .as_ref()
1024                    .unwrap()
1025                    .originating_vehicle_container
1026                    .as_ref()
1027                    .unwrap()
1028                    .speed,
1029                1600
1030            );
1031            assert_eq!(
1032                serde_json::to_string(&cpm).unwrap(),
1033                remove_whitespace(json)
1034            );
1035        } else {
1036            panic!("no cpm deserialized");
1037        };
1038    }
1039
1040    #[test]
1041    fn it_can_deserialize_then_serialize_a_full_cpm() {
1042        let json = full_cpm();
1043        let cpm: Exchange = serde_json::from_str(json).unwrap();
1044        assert_eq!(cpm.timestamp, 1574778515425);
1045        if let Message::CPM(message) = &cpm.message {
1046            assert_eq!(
1047                message
1048                    .station_data_container
1049                    .as_ref()
1050                    .unwrap()
1051                    .originating_vehicle_container
1052                    .as_ref()
1053                    .unwrap()
1054                    .speed,
1055                1600
1056            );
1057            assert_eq!(
1058                message.sensor_information_container[0]
1059                    .detection_area
1060                    .vehicle_sensor
1061                    .as_ref()
1062                    .unwrap()
1063                    .x_sensor_offset,
1064                -3094
1065            );
1066            assert_eq!(
1067                serde_json::to_string(&cpm).unwrap(),
1068                remove_whitespace(json)
1069            );
1070        } else {
1071            panic!("no cpm deserialized");
1072        };
1073    }
1074
1075    #[test]
1076    #[should_panic]
1077    fn it_should_panic_when_deserializing_a_cam_without_timestamp() {
1078        let json = bad_cam_without_timestamp();
1079        let _: Exchange = serde_json::from_str(json).unwrap();
1080    }
1081
1082    #[test]
1083    #[should_panic]
1084    fn it_should_panic_when_deserializing_a_denm_with_timestamp_as_string() {
1085        let json = bad_denm_with_string_timestamp();
1086        let _: Exchange = serde_json::from_str(json).unwrap();
1087    }
1088
1089    #[test]
1090    #[should_panic]
1091    fn it_should_panic_when_deserializing_a_cpm_without_timestamp() {
1092        let json = bad_cpm_with_negative_timestamp();
1093        let _: Exchange = serde_json::from_str(json).unwrap();
1094    }
1095
1096    #[test]
1097    #[should_panic]
1098    fn it_should_panic_when_deserializing_a_denm_with_protocol_version_bigger_than_u8() {
1099        let json = bad_denm_with_protocol_version_u32();
1100        let _: Exchange = serde_json::from_str(json).unwrap();
1101    }
1102}