ros_pointcloud2 0.6.0

Customizable conversions for working with sensor_msgs/PointCloud2.
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
1421
1422
1423
1424
1425
1426
1427
1428
1429
1430
1431
1432
1433
1434
1435
1436
1437
1438
1439
1440
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
1481
1482
1483
1484
1485
1486
1487
1488
1489
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
1518
1519
1520
1521
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
1544
1545
1546
1547
1548
1549
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
1563
1564
1565
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
1608
1609
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
//! A PointCloud2 message conversion library.
//!
//! The library provides the [`PointCloud2Msg`] type, which implements conversions to and from `Vec` and (parallel) iterators.
//!
//! Vector conversions are optimized for direct copy. They are useful when you just move similar data around. They are usually a good default.
//! - [`try_from_vec`](PointCloud2Msg::try_from_vec)
//! - [`try_into_vec`](PointCloud2Msg::try_into_vec)
//!
//! You can use the iterator functions for more control over the conversion process.
//! - [`try_from_iter`](PointCloud2Msg::try_from_iter)
//! - [`try_into_iter`](PointCloud2Msg::try_into_iter)
//!
//! These feature predictable performance but they do not scale well with large clouds. Learn more about that in the [performance section](https://github.com/stelzo/ros_pointcloud2?tab=readme-ov-file#performance) of the repository.
//! The iterators are useful when your conversions are more complex than a simple copy or the cloud is small enough.
//!
//! When the cloud is getting larger or you are doing a lot of processing per point, switch to the parallel iterators.
//! - [`try_into_par_iter`](PointCloud2Msg::try_into_par_iter) requires `rayon` feature
//! - [`try_from_par_iter`](PointCloud2Msg::try_from_par_iter) requires `rayon` feature
//!
//! For ROS interoperability, there are integrations available with feature flags. If you miss a message type, please open an issue or a PR.
//! See the [`ros`] module for more information on how to integrate more libraries.
//!
//! Common point types like [`PointXYZ`](points::PointXYZ) or [`PointXYZI`](points::PointXYZI) are provided. See the full list [`here`](points). You can easily add any additional custom type.
//! See [custom_enum_field_filter.rs](https://github.com/stelzo/ros_pointcloud2/blob/main/rpcl2/examples/custom_enum_field_filter.rs) for an example.
//!
//! # Minimal Example
//! ```
//! use ros_pointcloud2::prelude::*;
//!
//! let cloud_points = vec![
//!     PointXYZI::new(9.6, 42.0, -6.2, 0.1),
//!     PointXYZI::new(46.0, 5.47, 0.5, 0.1),
//! ];
//! let cloud_copy = cloud_points.clone(); // For equality test later.
//!
//! let out_msg = PointCloud2Msg::try_from_iter(&cloud_points).unwrap();
//!
//! // Convert to your ROS crate message type.
//! // let msg: r2r::sensor_msgs::msg::PointCloud2 = in_msg.into();
//! // Publish ...
//!
//! // ... now incoming from a topic.
//! // let in_msg: PointCloud2Msg = msg.into();
//! let in_msg = out_msg;
//!
//! let processed_cloud = in_msg.try_into_iter().unwrap()
//!     .map(|point: PointXYZ| { // Define the data you want from the point.
//!         // Some logic here.
//!         PointXYZI::new(point.x, point.y, point.z, 0.1)
//!     }).collect::<Vec<_>>();
//!
//! assert_eq!(processed_cloud, cloud_copy);
//! ```
//!
//! # Features
//! - r2r_msg — Integration for the ROS2 library [r2r](https://github.com/sequenceplanner/r2r).
//! - rosrust_msg — Integration with the [rosrust](https://github.com/adnanademovic/rosrust) library for ROS1 message types.
//! - safe_drive — Integration with the [safe_drive](https://github.com/tier4/safe_drive) bindings for ROS2.
//! - ros2-interfaces-jazzy-serde — Integration for the ros2-client compatible [ros2-interfaces-jazzy-serde](https://github.com/stelzo/ros2-interfaces-jazzy-serde) pre-built messages for ROS2 Jazzy.
//! - ros2-interfaces-jazzy-rkyv — Integration with the [ros2-interfaces-jazzy-rkyv](https://github.com/stelzo/ros2-interfaces-jazzy-rkyv) pre-built messages for ROS2 Jazzy with rkyv (de)serialization, typically used outside of ROS.
//! - derive — Offers implementations for the [`PointConvertible`] trait needed for custom points.
//! - rayon — Parallel iterator support for `_par_iter` functions.
//! - nalgebra — Predefined points offer a nalgebra typed getter for coordinates (e.g. [`xyz`](points::PointXYZ::xyz)).
//! - std *(enabled by default)* — Omit this feature to use this library in no_std environments. ROS integrations and 'rayon' will not work with no_std.
//!
//! # Custom Points
//! Implement [`PointConvertible`] for your point with the `derive` feature or manually.
//!
//! ## Derive (recommended)
//! ```ignore
//! #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
//! #[repr(C, align(4))]
//! pub struct MyPointXYZI {
//!     pub x: f32,
//!     pub y: f32,
//!     pub z: f32,
//!     #[ros(rename("i"))]
//!     pub intensity: f32,
//! }
//! ```
//!
//! ## Manual
//! ```
//! use ros_pointcloud2::prelude::*;
//!
//! #[derive(Clone, Debug, PartialEq, Copy, Default)]
//! #[repr(C, align(4))]
//! pub struct MyPointXYZI {
//!     pub x: f32,
//!     pub y: f32,
//!     pub z: f32,
//!     pub intensity: f32,
//! }
//!
//! impl MyPointXYZI {
//!     pub fn new(x: f32, y: f32, z: f32, intensity: f32) -> Self {
//!         Self { x, y, z, intensity }
//!     }
//! }
//!
//! impl From<IPoint<4>> for MyPointXYZI {
//!     fn from(point: IPoint<4>) -> Self {
//!         Self::new(point[0].get(), point[1].get(), point[2].get(), point[3].get())
//!     }
//! }
//!
//! impl From<MyPointXYZI> for IPoint<4> {
//!     fn from(point: MyPointXYZI) -> Self {
//!         [point.x.into(), point.y.into(), point.z.into(), point.intensity.into()].into()
//!     }
//! }
//!
//! unsafe impl PointConvertible<4> for MyPointXYZI {
//!     fn layout() -> LayoutDescription {
//!         LayoutDescription::new(&[
//!             LayoutField::new("x", "f32", 4),
//!             LayoutField::new("y", "f32", 4),
//!             LayoutField::new("z", "f32", 4),
//!             LayoutField::new("intensity", "f32", 4),
//!         ])
//!     }
//! }
//!
//! let first_p = MyPointXYZI::new(1.0, 2.0, 3.0, 0.5);
//! let cloud_points = vec![first_p, MyPointXYZI::new(4.0, 5.0, 6.0, 0.5)];
//! let msg_out = PointCloud2Msg::try_from_iter(&cloud_points).unwrap();
//! let cloud_points_out: Vec<MyPointXYZI> = msg_out.try_into_iter().unwrap().collect();
//! assert_eq!(first_p, *cloud_points_out.first().unwrap());
//! ```
#![crate_type = "lib"]
#![cfg_attr(docsrs, feature(doc_cfg))]
#![doc(html_root_url = "https://docs.rs/ros_pointcloud2/0.6.0")]
#![warn(clippy::print_stderr)]
#![warn(clippy::print_stdout)]
#![warn(clippy::unwrap_used)]
#![warn(clippy::expect_used)]
#![warn(clippy::cargo)]
#![warn(clippy::std_instead_of_core)]
#![warn(clippy::alloc_instead_of_core)]
#![warn(clippy::std_instead_of_alloc)]
#![cfg_attr(not(feature = "std"), no_std)]
// Setup an allocator with #[global_allocator]
// see: https://doc.rust-lang.org/std/alloc/trait.GlobalAlloc.html
#![allow(unexpected_cfgs)]
#![allow(clippy::multiple_crate_versions)] // nalgebra 0.34 uses many glam versions, fix needs https://github.com/rust-lang/cargo/issues/10801

pub mod points;
pub mod prelude;
pub mod ros;

pub mod iterator;

use crate::ros::{HeaderMsg, PointFieldMsg};

use core::str::FromStr;

#[cfg(feature = "serde")]
use serde::{Deserialize, Serialize};

#[macro_use]
extern crate alloc;
use alloc::string::String;
use alloc::vec::Vec;

/// All errors that can occur while converting to or from the message type.
#[derive(Debug)]
pub enum MsgConversionError {
    InvalidFieldFormat,
    #[cfg(feature = "std")]
    UnsupportedFieldType(String),
    #[cfg(not(feature = "std"))]
    UnsupportedFieldType,
    DataLengthMismatch,
    FieldsNotFound(Vec<String>),
    UnsupportedFieldCount,
    NumberConversion,
    ExhaustedSource,
}

impl From<core::num::TryFromIntError> for MsgConversionError {
    fn from(_: core::num::TryFromIntError) -> Self {
        MsgConversionError::NumberConversion
    }
}

impl core::fmt::Display for MsgConversionError {
    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
        match self {
            MsgConversionError::InvalidFieldFormat => {
                write!(f, "The field does not match the expected datatype.")
            }
            #[cfg(feature = "std")]
            MsgConversionError::UnsupportedFieldType(datatype) => {
                write!(
                    f,
                    "The field datatype is not supported by the ROS message description: {datatype}"
                )
            }
            #[cfg(not(feature = "std"))]
            MsgConversionError::UnsupportedFieldType => {
                write!(
                    f,
                    "There is an unsupported field type in the ROS message description."
                )
            }
            MsgConversionError::DataLengthMismatch => {
                write!(f, "The length of the byte buffer in the message does not match the expected length computed from the fields, indicating a corrupted or malformed message.")
            }
            MsgConversionError::FieldsNotFound(fields) => {
                write!(f, "Some fields are not found in the message: {fields:?}")
            }
            MsgConversionError::UnsupportedFieldCount => {
                write!(
                    f,
                    "Only field_count 1 is supported for reading and writing."
                )
            }
            MsgConversionError::NumberConversion => {
                write!(f, "The number is too large to be converted into a PointCloud2 supported datatype.")
            }
            MsgConversionError::ExhaustedSource => {
                write!(
                    f,
                    "The conversion requests more data from the source type than is available."
                )
            }
        }
    }
}

#[allow(clippy::std_instead_of_core)] // will be stable soon (https://github.com/rust-lang/rust/issues/103765)
#[cfg(feature = "std")]
impl std::error::Error for MsgConversionError {
    fn source(&self) -> Option<&(dyn std::error::Error + 'static)> {
        None
    }
}

fn system_endian() -> Endian {
    if cfg!(target_endian = "big") {
        Endian::Big
    } else if cfg!(target_endian = "little") {
        Endian::Little
    } else {
        panic!("Unsupported Endian");
    }
}

/// Description of the memory layout of a type with named fields.
#[derive(Clone, Debug)]
pub struct LayoutDescription(Vec<LayoutField>);

impl LayoutDescription {
    pub fn new(fields: &[LayoutField]) -> Self {
        Self(fields.into())
    }
}

/// Enum to describe the field type and size in a padded or unpadded layout.
#[derive(Clone, Debug)]
pub enum LayoutField {
    Field {
        name: alloc::borrow::Cow<'static, str>,
        ty: alloc::borrow::Cow<'static, str>,
        size: usize,
    },
    Padding {
        size: usize,
    },
}

impl LayoutField {
    pub fn new(name: &'static str, ty: &'static str, size: usize) -> Self {
        LayoutField::Field {
            name: name.into(),
            ty: ty.into(),
            size,
        }
    }

    pub fn padding(size: usize) -> Self {
        LayoutField::Padding { size }
    }
}

/// The intermediate point cloud type for ROS integrations.
///
/// To assert consistency, the type should be build with the [`PointCloud2MsgBuilder`].
/// See the offical [ROS message description](https://docs.ros2.org/latest/api/sensor_msgs/msg/PointCloud2.html) for more information on the fields.
#[derive(Clone, Debug)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct PointCloud2Msg {
    pub header: HeaderMsg,
    pub dimensions: CloudDimensions,
    pub fields: Vec<PointFieldMsg>,
    pub endian: Endian,
    pub point_step: u32,
    pub row_step: u32,
    pub data: Vec<u8>,
    pub dense: Denseness,
}

/// Endianess encoding hint for the message.
#[derive(Default, Clone, Debug, PartialEq, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub enum Endian {
    Big,
    #[default]
    Little,
}

/// Density flag for the message. Writing sparse point clouds is not supported.
#[derive(Default, Clone, Debug, PartialEq, Copy)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub enum Denseness {
    #[default]
    Dense,
    Sparse,
}

#[derive(Clone, Debug, PartialEq)]
enum ByteSimilarity {
    Equal,
    Overlapping,
    Different,
}

/// Creating a [`CloudDimensions`] type with the builder pattern to avoid invalid states when using 1-row point clouds.
#[derive(Clone, Debug)]
pub struct CloudDimensionsBuilder(usize);

impl CloudDimensionsBuilder {
    #[must_use]
    pub fn new_with_width(width: usize) -> Self {
        Self(width)
    }

    pub fn build(self) -> Result<CloudDimensions, MsgConversionError> {
        let width = match u32::try_from(self.0) {
            Ok(w) => w,
            Err(_) => return Err(MsgConversionError::NumberConversion),
        };

        Ok(CloudDimensions {
            width,
            height: u32::from(self.0 > 0),
        })
    }
}

/// Creating a [`PointCloud2Msg`] with the builder pattern to avoid invalid states.
#[derive(Clone, Debug, Default)]
pub struct PointCloud2MsgBuilder {
    header: HeaderMsg,
    width: u32,
    fields: Vec<PointFieldMsg>,
    is_big_endian: bool,
    point_step: u32,
    row_step: u32,
    data: Vec<u8>,
    is_dense: bool,
}

impl PointCloud2MsgBuilder {
    #[must_use]
    pub fn new() -> Self {
        Self::default()
    }

    #[must_use]
    pub fn header(mut self, header: HeaderMsg) -> Self {
        self.header = header;
        self
    }

    #[must_use]
    pub fn width(mut self, width: u32) -> Self {
        self.width = width;
        self
    }

    #[must_use]
    pub fn fields(mut self, fields: Vec<PointFieldMsg>) -> Self {
        self.fields = fields;
        self
    }

    #[must_use]
    pub fn endian(mut self, is_big_endian: bool) -> Self {
        self.is_big_endian = is_big_endian;
        self
    }

    #[must_use]
    pub fn point_step(mut self, point_step: u32) -> Self {
        self.point_step = point_step;
        self
    }

    #[must_use]
    pub fn row_step(mut self, row_step: u32) -> Self {
        self.row_step = row_step;
        self
    }

    #[must_use]
    pub fn data(mut self, data: Vec<u8>) -> Self {
        self.data = data;
        self
    }

    #[must_use]
    pub fn dense(mut self, is_dense: bool) -> Self {
        self.is_dense = is_dense;
        self
    }

    /// Build the [`PointCloud2Msg`] from the builder.
    ///
    /// # Errors
    /// Returns an error if the fields are empty, the field count is not 1, the field format is invalid, the data length does not match the point step, or the field size is too large.
    pub fn build(self) -> Result<PointCloud2Msg, MsgConversionError> {
        if self.fields.is_empty() {
            return Err(MsgConversionError::FieldsNotFound(vec![]));
        }

        if self.fields.iter().any(|f| f.count != 1) {
            return Err(MsgConversionError::UnsupportedFieldCount);
        }

        let fields_size = self
            .fields
            .iter()
            .map(FieldDatatype::try_from)
            .collect::<Result<Vec<_>, _>>()?
            .iter()
            .map(|f| f.size() as u32)
            .sum::<_>();

        if self.point_step < fields_size {
            return Err(MsgConversionError::InvalidFieldFormat);
        }

        if self.data.len() as u32 % self.point_step != 0 {
            return Err(MsgConversionError::DataLengthMismatch);
        }

        Ok(PointCloud2Msg {
            header: self.header,
            dimensions: CloudDimensionsBuilder::new_with_width(self.width as usize).build()?,
            fields: self.fields,
            endian: if self.is_big_endian {
                Endian::Big
            } else {
                Endian::Little
            },
            point_step: self.point_step,
            row_step: self.row_step,
            data: self.data,
            dense: if self.is_dense {
                Denseness::Dense
            } else {
                Denseness::Sparse
            },
        })
    }
}

/// Dimensions of the point cloud as width and height.
#[derive(Clone, Debug, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub struct CloudDimensions {
    pub width: u32,
    pub height: u32,
}

fn ordered_field_names<const N: usize, C: PointConvertible<N>>() -> Vec<String> {
    C::layout()
        .0
        .iter()
        .filter(|field| {
            matches!(
                field,
                LayoutField::Field {
                    name: _,
                    ty: _,
                    size: _,
                }
            )
        })
        .map(|field| match field {
            LayoutField::Field {
                name,
                ty: _,
                size: _,
            } => name.as_ref().into(),
            _ => unreachable!("Fields must be filtered before."),
        })
        .collect()
}

impl PointCloud2Msg {
    #[inline]
    fn byte_similarity<const N: usize, C>(&self) -> Result<ByteSimilarity, MsgConversionError>
    where
        C: PointConvertible<N>,
    {
        let field_names = ordered_field_names::<N, C>();
        let target_layout = KnownLayoutInfo::try_from(C::layout())?;

        debug_assert!(field_names.len() <= target_layout.fields.len());
        debug_assert!(self.fields.len() >= target_layout.fields.len());

        let mut offset: u32 = 0;
        let mut field_counter = 0;
        for f in target_layout.fields.iter() {
            match f {
                PointField::Field {
                    datatype,
                    size,
                    count,
                } => {
                    if field_counter >= self.fields.len() || field_counter >= field_names.len() {
                        return Err(MsgConversionError::ExhaustedSource);
                    }

                    let msg_f = unsafe { self.fields.get_unchecked(field_counter) };
                    let f_translated = unsafe { field_names.get_unchecked(field_counter) };
                    field_counter += 1;

                    if msg_f.name != *f_translated
                        || msg_f.offset != offset
                        || msg_f.datatype != *datatype
                        || msg_f.count != 1
                    {
                        return Ok(ByteSimilarity::Different);
                    }

                    offset += size * count;
                }
                PointField::Padding(size) => {
                    offset += size;
                }
            }
        }

        Ok(if offset == self.point_step {
            ByteSimilarity::Equal
        } else {
            ByteSimilarity::Overlapping
        })
    }

    /// Create a [`PointCloud2Msg`] from any iterable type that implements [`PointConvertible`].
    ///
    /// # Example
    /// ```
    /// use ros_pointcloud2::prelude::*;
    ///
    /// let cloud_points: Vec<PointXYZ> = vec![
    ///     PointXYZ::new(1.0, 2.0, 3.0),
    ///     PointXYZ::new(4.0, 5.0, 6.0),
    /// ];
    ///
    // let msg_out = PointCloud2Msg::try_from_iter(&cloud_points).unwrap();
    /// ```
    pub fn try_from_iter<'a, const N: usize, C>(
        iterable: impl IntoIterator<Item = &'a C>,
    ) -> Result<Self, MsgConversionError>
    where
        C: PointConvertible<N> + 'a,
    {
        let (mut cloud, point_step) = {
            let point: IPoint<N> = C::default().into();
            debug_assert!(point.fields.len() == N);

            let field_names = crate::ordered_field_names::<N, C>();
            debug_assert!(field_names.len() == N);

            let mut pdata_offsets_acc: u32 = 0;
            let mut fields = vec![PointFieldMsg::default(); N];
            let field_count: u32 = 1;
            for ((pdata_entry, field_name), field_val) in point
                .fields
                .into_iter()
                .zip(field_names.into_iter())
                .zip(fields.iter_mut())
            {
                let datatype_code = pdata_entry.datatype.into();
                let _ = FieldDatatype::try_from(datatype_code)?;

                *field_val = PointFieldMsg {
                    name: field_name,
                    offset: pdata_offsets_acc,
                    datatype: datatype_code,
                    count: 1,
                };

                pdata_offsets_acc += field_count * pdata_entry.datatype.size() as u32;
            }

            (
                PointCloud2MsgBuilder::new()
                    .fields(fields)
                    .point_step(pdata_offsets_acc),
                pdata_offsets_acc,
            )
        };
        let mut cloud_width = 0;

        iterable.into_iter().for_each(|pointdata| {
            let point: IPoint<N> = (*pointdata).into();

            point.fields.iter().for_each(|pdata| {
                let truncated_bytes = unsafe {
                    core::slice::from_raw_parts(pdata.bytes.as_ptr(), pdata.datatype.size())
                };
                cloud.data.extend_from_slice(truncated_bytes);
            });

            cloud_width += 1;
        });

        cloud = cloud.width(cloud_width);
        cloud = cloud.row_step(cloud_width * point_step);

        cloud.build()
    }

    /// Create a PointCloud2Msg from a parallel iterator. Requires the `rayon` and `derive` feature to be enabled.
    #[cfg(feature = "rayon")]
    #[cfg_attr(docsrs, doc(cfg(feature = "rayon")))]
    pub fn try_from_par_iter<const N: usize, C>(
        iterable: impl rayon::iter::ParallelIterator<Item = C>,
    ) -> Result<Self, MsgConversionError>
    where
        C: PointConvertible<N> + Send + Sync,
    {
        Self::try_from_vec(&iterable.collect::<Vec<_>>())
    }

    /// Create a [`PointCloud2Msg`] from a Vec of points.
    /// Since the point type is known at compile time, the conversion is done by direct copy.
    ///
    /// # Example
    /// ```
    /// use ros_pointcloud2::prelude::*;
    ///
    /// let cloud_points: Vec<PointXYZ> = vec![
    ///     PointXYZ::new(1.0, 2.0, 3.0),
    ///     PointXYZ::new(4.0, 5.0, 6.0),
    /// ];
    ///
    /// let msg_out = PointCloud2Msg::try_from_vec(&cloud_points).unwrap();
    /// ```
    ///
    /// # Errors
    /// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
    pub fn try_from_vec<const N: usize, C>(vec: &[C]) -> Result<Self, MsgConversionError>
    where
        C: PointConvertible<N>,
    {
        match (system_endian(), Endian::default()) {
            (Endian::Big, Endian::Big) | (Endian::Little, Endian::Little) => {
                let (mut cloud, point_step) = {
                    let point: IPoint<N> = C::default().into();
                    debug_assert!(point.fields.len() == N);

                    let field_names = crate::ordered_field_names::<N, C>();
                    debug_assert!(field_names.len() == N);

                    let layout = KnownLayoutInfo::try_from(C::layout())?;
                    debug_assert!(field_names.len() <= layout.fields.len());

                    let mut offset = 0;
                    let mut fields: Vec<PointFieldMsg> = Vec::with_capacity(field_names.len());
                    for f in layout.fields.into_iter() {
                        match f {
                            PointField::Field {
                                datatype,
                                size,
                                count,
                            } => {
                                fields.push(PointFieldMsg {
                                    name: field_names[fields.len()].clone(),
                                    offset,
                                    datatype,
                                    ..Default::default()
                                });
                                offset += size * count;
                            }
                            PointField::Padding(size) => {
                                offset += size;
                            }
                        }
                    }

                    (
                        PointCloud2MsgBuilder::new()
                            .fields(fields)
                            .point_step(offset),
                        offset,
                    )
                };

                let bytes_total = vec.len() * point_step as usize;
                cloud.data.resize(bytes_total, u8::default());
                let raw_data: *mut C = cloud.data.as_mut_ptr() as *mut C;
                unsafe {
                    core::ptr::copy_nonoverlapping(
                        vec.as_ptr().cast::<u8>(),
                        raw_data.cast::<u8>(),
                        bytes_total,
                    );
                }

                Ok(cloud
                    .width(vec.len() as u32)
                    .row_step(vec.len() as u32 * point_step)
                    .build()?)
            }
            _ => Self::try_from_iter(vec.iter()),
        }
    }

    /// Convert the [`PointCloud2Msg`] to a Vec of points.
    ///
    /// # Example
    /// ```
    /// use ros_pointcloud2::prelude::*;
    ///
    /// let cloud_points: Vec<PointXYZI> = vec![
    ///     PointXYZI::new(1.0, 2.0, 3.0, 0.5),
    ///     PointXYZI::new(4.0, 5.0, 6.0, 1.1),
    /// ];
    ///
    /// let msg_out = PointCloud2Msg::try_from_vec(&cloud_points).unwrap();
    /// let cloud_points_out: Vec<PointXYZ> = msg_out.try_into_vec().unwrap();
    /// assert_eq!(1.0, cloud_points_out.get(0).unwrap().x);
    /// ```
    ///
    /// # Errors
    /// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
    pub fn try_into_vec<const N: usize, C>(self) -> Result<Vec<C>, MsgConversionError>
    where
        C: PointConvertible<N>,
    {
        match (system_endian(), self.endian) {
            (Endian::Big, Endian::Big) | (Endian::Little, Endian::Little) => {
                let bytematch = match self.byte_similarity::<N, C>()? {
                    ByteSimilarity::Equal => true,
                    ByteSimilarity::Overlapping => false,
                    ByteSimilarity::Different => return Ok(self.try_into_iter()?.collect()),
                };

                let cloud_width = self.dimensions.width as usize;
                let point_step = self.point_step as usize;
                let mut vec: Vec<C> = Vec::with_capacity(cloud_width);
                if bytematch {
                    unsafe {
                        core::ptr::copy_nonoverlapping(
                            self.data.as_ptr(),
                            vec.as_mut_ptr().cast::<u8>(),
                            self.data.len(),
                        );
                        vec.set_len(cloud_width);
                    }
                } else {
                    unsafe {
                        for i in 0..cloud_width {
                            let point_ptr = self.data.as_ptr().add(i * point_step).cast::<C>();
                            let point = point_ptr.read();
                            vec.push(point);
                        }
                    }
                }

                Ok(vec)
            }
            _ => Ok(self.try_into_iter()?.collect()), // Endianess does not match, read point by point since Endian is read at conversion time.
        }
    }

    /// Convert the [`PointCloud2Msg`] to an iterator.
    ///
    /// # Example
    /// ```
    /// use ros_pointcloud2::prelude::*;
    ///
    /// let cloud_points: Vec<PointXYZI> = vec![
    ///     PointXYZI::new(1.0, 2.0, 3.0, 0.5),
    ///     PointXYZI::new(4.0, 5.0, 6.0, 1.1),
    /// ];
    ///
    /// let msg_out = PointCloud2Msg::try_from_iter(&cloud_points).unwrap();
    /// let cloud_points_out = msg_out.try_into_iter().unwrap().collect::<Vec<PointXYZ>>();
    /// ```
    /// # Errors
    /// Returns an error if the byte buffer does not match the expected layout or the message contains other discrepancies.
    pub fn try_into_iter<const N: usize, C>(
        self,
    ) -> Result<impl Iterator<Item = C>, MsgConversionError>
    where
        C: PointConvertible<N>,
    {
        iterator::PointCloudIterator::try_from(self)
    }

    /// Convert the PointCloud2Msg to a parallel iterator. Requires the `rayon` feature to be enabled.
    ///
    /// # Example
    /// ```
    /// use ros_pointcloud2::prelude::*;
    ///
    /// let cloud_points: Vec<PointXYZI> = vec![
    ///    PointXYZI::new(1.0, 2.0, 3.0, 0.5),
    ///    PointXYZI::new(4.0, 5.0, 6.0, 1.1),
    /// ];
    ///
    /// let msg_out = PointCloud2Msg::try_from_iter(&cloud_points).unwrap();
    /// let cloud_points_out = msg_out.try_into_par_iter().unwrap().collect::<Vec<PointXYZ>>();
    /// assert_eq!(2, cloud_points_out.len());
    /// ```
    #[cfg_attr(docsrs, doc(cfg(feature = "rayon")))]
    #[cfg(feature = "rayon")]
    pub fn try_into_par_iter<const N: usize, C>(
        self,
    ) -> Result<impl rayon::iter::ParallelIterator<Item = C>, MsgConversionError>
    where
        C: PointConvertible<N> + Send + Sync,
    {
        iterator::PointCloudIterator::try_from(self)
    }
}

/// Internal point representation. It is used to store the point data entries.
///
/// In each iteration, an internal point representation is converted to the desired point type.
/// Implement the `From` traits for your point type to use the conversion.
///
/// See the [`PointConvertible`] trait for more information.
pub struct IPoint<const N: usize> {
    fields: [PointData; N],
}

impl<const N: usize> core::ops::Index<usize> for IPoint<N> {
    type Output = PointData;

    fn index(&self, index: usize) -> &Self::Output {
        &self.fields[index]
    }
}

impl<const N: usize> From<[PointData; N]> for IPoint<N> {
    fn from(fields: [PointData; N]) -> Self {
        Self { fields }
    }
}

/// Trait to enable point conversions on the fly.
///
/// Implement this trait for your custom point you want to read or write in the message.
/// It is strongly recommended to enable the `derive` feature and use the `#[derive(PointConvertible)]` macro.
/// This prevents common errors when implementing this trait by hand.
///
/// Be aware that Rust does not guarantee the memory layout of structs. Learn more [here](https://doc.rust-lang.org/reference/type-layout.html).
/// To make layouting more predictable and thus faster for C++ node interactions, use the `#[repr(C)]` attribute on your struct.
/// An example for diverging point layouts with padding can be seen in the source code of [this](points::PointXYZRGBA::layout) implementation.
///
/// The generic parameter `N` is the number of fields in the point type. There can be more (hidden) fields that pad the layout but they do not count for the N.
/// For
///
/// # Derive
/// ```ignore
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default, PointConvertible)]
/// #[repr(C, align(4))]
/// pub struct MyPointXYZL {
///     pub x: f32,
///     pub y: f32,
///     pub z: f32,
///     #[field(rename("l"))]
///     pub label: u8,
/// }
/// ```
///
/// # Manual
/// ```
/// use ros_pointcloud2::prelude::*;
///
/// #[derive(Clone, Debug, PartialEq, Copy, Default)]
/// #[repr(C, align(4))]
/// pub struct MyPointXYZL {
///     pub x: f32,
///     pub y: f32,
///     pub z: f32,
///     pub label: u8,
/// }
///
/// impl From<MyPointXYZL> for IPoint<4> {
///     fn from(point: MyPointXYZL) -> Self {
///         [point.x.into(), point.y.into(), point.z.into(), point.label.into()].into()
///     }
/// }
///
/// impl From<IPoint<4>> for MyPointXYZL {
///     fn from(point: IPoint<4>) -> Self {
///         Self {
///             x: point[0].get(),
///             y: point[1].get(),
///             z: point[2].get(),
///             label: point[3].get(),
///         }
///     }
/// }
///
/// unsafe impl PointConvertible<4> for MyPointXYZL {
///     fn layout() -> LayoutDescription {
///         LayoutDescription::new(&[
///             LayoutField::new("x", "f32", 4),
///             LayoutField::new("y", "f32", 4),
///             LayoutField::new("z", "f32", 4),
///             LayoutField::new("l", "u8", 1),
///             LayoutField::padding(3),
///         ])
///     }
/// }
/// ```
/// # Safety
/// The layout is used for raw memory interpretation, where safety can not be guaranteed by the compiler.
/// Take care when implementing the layout, especially in combination with `#[repr]` or use the `derive` feature when possible to prevent common errors.
pub unsafe trait PointConvertible<const N: usize>:
    From<IPoint<N>> + Into<IPoint<N>> + Default + Sized + Copy
{
    fn layout() -> LayoutDescription;
}

#[derive(Debug, Clone)]
enum PointField {
    Padding(u32),
    Field { size: u32, datatype: u8, count: u32 },
}

#[derive(Debug, Clone)]
struct KnownLayoutInfo {
    fields: Vec<PointField>,
}

impl TryFrom<LayoutField> for PointField {
    type Error = MsgConversionError;

    fn try_from(f: LayoutField) -> Result<Self, Self::Error> {
        match f {
            LayoutField::Field { name: _, ty, size } => {
                let typename: String = ty.into_owned().to_lowercase();
                let datatype = FieldDatatype::from_str(typename.as_str())?;
                Ok(Self::Field {
                    size: size.try_into()?,
                    datatype: datatype.into(),
                    count: 1,
                })
            }
            LayoutField::Padding { size } => Ok(Self::Padding(size.try_into()?)),
        }
    }
}

impl TryFrom<LayoutDescription> for KnownLayoutInfo {
    type Error = MsgConversionError;

    fn try_from(t: LayoutDescription) -> Result<Self, Self::Error> {
        let fields: Vec<PointField> =
            t.0.into_iter()
                .map(PointField::try_from)
                .collect::<Result<Vec<_>, _>>()?;
        Ok(Self { fields })
    }
}

/// Single data representation for a point.
///
/// This struct is used to store data fields in a fixed size byte buffer along the with the
/// datatype that is encoded so that it can be decoded later.
///
/// # Example
/// ```
/// use ros_pointcloud2::PointData;
///
/// let original_data: f64 = 1.0;
/// let pdata = PointData::new(original_data);
/// let my_data: f64 = pdata.get();
/// ```
#[derive(Debug, Clone, Copy)]
pub struct PointData {
    bytes: [u8; core::mem::size_of::<f64>()],
    endian: Endian,
    datatype: FieldDatatype,
}

impl Default for PointData {
    fn default() -> Self {
        Self {
            bytes: [u8::default(); core::mem::size_of::<f64>()],
            datatype: FieldDatatype::F32,
            endian: Endian::default(),
        }
    }
}

impl PointData {
    /// Create a new [`PointData`] from a value.
    ///
    /// # Example
    /// ```
    /// let pdata = ros_pointcloud2::PointData::new(1.0);
    /// ```
    #[inline]
    pub fn new<T: FromBytes>(value: T) -> Self {
        Self {
            bytes: value.into().raw(),
            datatype: T::field_datatype(),
            ..Default::default()
        }
    }

    #[inline]
    fn from_buffer(data: &[u8], offset: usize, datatype: FieldDatatype, endian: Endian) -> Self {
        debug_assert!(data.len() >= offset + datatype.size());
        let mut bytes = [u8::default(); core::mem::size_of::<f64>()];
        unsafe {
            let data_ptr = data.as_ptr().add(offset);
            core::ptr::copy_nonoverlapping(data_ptr, bytes.as_mut_ptr(), datatype.size());
        }

        Self {
            bytes,
            endian,
            datatype,
        }
    }

    /// Get the numeric value from the [`PointData`] description.
    ///
    /// # Example
    /// ```
    /// let original_data: f64 = 1.0;
    /// let pdata = ros_pointcloud2::PointData::new(original_data);
    /// let my_data: f64 = pdata.get();
    /// ```
    #[must_use]
    pub fn get<T: FromBytes>(&self) -> T {
        match self.endian {
            Endian::Big => T::from_be_bytes(PointDataBuffer::new(self.bytes)),
            Endian::Little => T::from_le_bytes(PointDataBuffer::new(self.bytes)),
        }
    }
}

impl From<f32> for PointData {
    fn from(value: f32) -> Self {
        Self::new(value)
    }
}

impl From<f64> for PointData {
    fn from(value: f64) -> Self {
        Self::new(value)
    }
}

impl From<i32> for PointData {
    fn from(value: i32) -> Self {
        Self::new(value)
    }
}

impl From<u8> for PointData {
    fn from(value: u8) -> Self {
        Self::new(value)
    }
}

impl From<u16> for PointData {
    fn from(value: u16) -> Self {
        Self::new(value)
    }
}

impl From<u32> for PointData {
    fn from(value: u32) -> Self {
        Self::new(value)
    }
}

impl From<i8> for PointData {
    fn from(value: i8) -> Self {
        Self::new(value)
    }
}

impl From<i16> for PointData {
    fn from(value: i16) -> Self {
        Self::new(value)
    }
}

/// Datatypes from the [`PointFieldMsg`].
#[derive(Default, Clone, Debug, PartialEq, Copy)]
pub enum FieldDatatype {
    F32,
    F64,
    I32,
    U8,
    U16,
    #[default]
    U32,
    I8,
    I16,

    /// While RGB is not officially supported by ROS, it is used in the tooling as a packed f32.
    /// To make it easy to work with and avoid packing code, the [`RGB`](points::RGB) union is supported here and handled like a f32.
    RGB,
}

impl FieldDatatype {
    #[must_use]
    pub fn size(&self) -> usize {
        match self {
            FieldDatatype::U8 => core::mem::size_of::<u8>(),
            FieldDatatype::U16 => core::mem::size_of::<u16>(),
            FieldDatatype::U32 => core::mem::size_of::<u32>(),
            FieldDatatype::I8 => core::mem::size_of::<i8>(),
            FieldDatatype::I16 => core::mem::size_of::<i16>(),
            FieldDatatype::I32 => core::mem::size_of::<i32>(),
            FieldDatatype::F32 | FieldDatatype::RGB => core::mem::size_of::<f32>(), // packed in f32
            FieldDatatype::F64 => core::mem::size_of::<f64>(),
        }
    }
}

impl core::str::FromStr for FieldDatatype {
    type Err = MsgConversionError;

    fn from_str(s: &str) -> Result<Self, Self::Err> {
        match s {
            "f32" => Ok(FieldDatatype::F32),
            "f64" => Ok(FieldDatatype::F64),
            "i32" => Ok(FieldDatatype::I32),
            "u8" => Ok(FieldDatatype::U8),
            "u16" => Ok(FieldDatatype::U16),
            "u32" => Ok(FieldDatatype::U32),
            "i8" => Ok(FieldDatatype::I8),
            "i16" => Ok(FieldDatatype::I16),
            "rgb" => Ok(FieldDatatype::RGB),
            #[cfg(feature = "std")]
            _ => Err(MsgConversionError::UnsupportedFieldType(s.into())),
            #[cfg(not(feature = "std"))]
            _ => Err(MsgConversionError::UnsupportedFieldType),
        }
    }
}

/// Getter trait for the datatype of a field value.
pub trait GetFieldDatatype {
    fn field_datatype() -> FieldDatatype;
}

impl GetFieldDatatype for f32 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::F32
    }
}

impl GetFieldDatatype for f64 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::F64
    }
}

impl GetFieldDatatype for i32 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::I32
    }
}

impl GetFieldDatatype for u8 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::U8
    }
}

impl GetFieldDatatype for u16 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::U16
    }
}

impl GetFieldDatatype for u32 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::U32
    }
}

impl GetFieldDatatype for i8 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::I8
    }
}

impl GetFieldDatatype for i16 {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::I16
    }
}

/// Convenience implementation for the RGB union.
impl GetFieldDatatype for crate::points::RGB {
    fn field_datatype() -> FieldDatatype {
        FieldDatatype::RGB
    }
}

impl TryFrom<u8> for FieldDatatype {
    type Error = MsgConversionError;

    fn try_from(value: u8) -> Result<Self, Self::Error> {
        match value {
            1 => Ok(FieldDatatype::I8),
            2 => Ok(FieldDatatype::U8),
            3 => Ok(FieldDatatype::I16),
            4 => Ok(FieldDatatype::U16),
            5 => Ok(FieldDatatype::I32),
            6 => Ok(FieldDatatype::U32),
            7 => Ok(FieldDatatype::F32),
            8 => Ok(FieldDatatype::F64),
            #[cfg(feature = "std")]
            _ => Err(MsgConversionError::UnsupportedFieldType(value.to_string())),
            #[cfg(not(feature = "std"))]
            _ => Err(MsgConversionError::UnsupportedFieldType),
        }
    }
}

impl From<FieldDatatype> for u8 {
    fn from(val: FieldDatatype) -> Self {
        match val {
            FieldDatatype::I8 => 1,
            FieldDatatype::U8 => 2,
            FieldDatatype::I16 => 3,
            FieldDatatype::U16 => 4,
            FieldDatatype::I32 => 5,
            FieldDatatype::U32 => 6,
            FieldDatatype::F32 | FieldDatatype::RGB => 7, // RGB is marked as f32 in the buffer
            FieldDatatype::F64 => 8,
        }
    }
}

impl TryFrom<&ros::PointFieldMsg> for FieldDatatype {
    type Error = MsgConversionError;

    fn try_from(value: &ros::PointFieldMsg) -> Result<Self, Self::Error> {
        Self::try_from(value.datatype)
    }
}

/// Byte buffer alias for endian-aware point data reading and writing.
///
/// It uses a fixed size buffer of 8 bytes since the largest supported datatype for [`PointFieldMsg`] is f64.
pub struct PointDataBuffer([u8; 8]);

impl core::ops::Index<usize> for PointDataBuffer {
    type Output = u8;

    fn index(&self, index: usize) -> &Self::Output {
        &self.0[index]
    }
}

impl PointDataBuffer {
    #[must_use]
    pub fn new(data: [u8; 8]) -> Self {
        Self(data)
    }

    #[must_use]
    pub fn as_slice(&self) -> &[u8] {
        &self.0
    }

    #[must_use]
    pub fn raw(self) -> [u8; 8] {
        self.0
    }

    #[must_use]
    pub fn from_slice(data: &[u8]) -> Self {
        let mut buffer = [0; 8];
        data.iter().enumerate().for_each(|(i, &v)| buffer[i] = v);
        Self(buffer)
    }
}

impl From<&[u8]> for PointDataBuffer {
    fn from(data: &[u8]) -> Self {
        Self::from_slice(data)
    }
}

impl<const N: usize> From<[u8; N]> for PointDataBuffer {
    fn from(data: [u8; N]) -> Self {
        Self::from(data.as_slice())
    }
}

impl From<i8> for PointDataBuffer {
    fn from(x: i8) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<i16> for PointDataBuffer {
    fn from(x: i16) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<u16> for PointDataBuffer {
    fn from(x: u16) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<i32> for PointDataBuffer {
    fn from(x: i32) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<u32> for PointDataBuffer {
    fn from(x: u32) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<f32> for PointDataBuffer {
    fn from(x: f32) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<f64> for PointDataBuffer {
    fn from(x: f64) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<u8> for PointDataBuffer {
    fn from(x: u8) -> Self {
        x.to_le_bytes().into()
    }
}

impl From<points::RGB> for PointDataBuffer {
    fn from(x: points::RGB) -> Self {
        x.raw().to_le_bytes().into()
    }
}

/// This trait is used to convert a byte slice to a primitive type.
/// All [`PointFieldMsg`] types are supported.
pub trait FromBytes: Default + Sized + Copy + GetFieldDatatype + Into<PointDataBuffer> {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self;
    fn from_le_bytes(bytes: PointDataBuffer) -> Self;
}

impl FromBytes for i8 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0]])
    }
}

impl FromBytes for i16 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0], bytes[1]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0], bytes[1]])
    }
}

impl FromBytes for u16 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0], bytes[1]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0], bytes[1]])
    }
}

impl FromBytes for u32 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }
}

impl FromBytes for f32 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }
}

impl FromBytes for points::RGB {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::new_from_packed_f32(f32::from_be_bytes([bytes[0], bytes[1], bytes[2], bytes[3]]))
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::new_from_packed_f32(f32::from_le_bytes([bytes[0], bytes[1], bytes[2], bytes[3]]))
    }
}

impl FromBytes for i32 {
    #[inline]
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }
    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0], bytes[1], bytes[2], bytes[3]])
    }
}

impl FromBytes for f64 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([
            bytes[0], bytes[1], bytes[2], bytes[3], bytes[4], bytes[5], bytes[6], bytes[7],
        ])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([
            bytes[0], bytes[1], bytes[2], bytes[3], bytes[4], bytes[5], bytes[6], bytes[7],
        ])
    }
}

impl FromBytes for u8 {
    fn from_be_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_be_bytes([bytes[0]])
    }

    fn from_le_bytes(bytes: PointDataBuffer) -> Self {
        Self::from_le_bytes([bytes[0]])
    }
}

mod test {
    #![allow(clippy::unwrap_used)]

    use crate::prelude::*;

    #[derive(Debug, Default, Clone, PartialEq, Copy)]
    #[repr(C)]
    struct PointA {
        x: f32,
        y: f32,
        z: f32,
        intensity: f32,
        t: u32,
        reflectivity: u16,
        ring: u16,
        ambient: u16,
        range: u32,
    }

    impl From<IPoint<9>> for PointA {
        fn from(point: IPoint<9>) -> Self {
            Self::new(point[0].get(), point[1].get(), point[2].get())
        }
    }

    impl From<PointA> for IPoint<9> {
        fn from(point: PointA) -> Self {
            [
                point.x.into(),
                point.y.into(),
                point.z.into(),
                point.intensity.into(),
                point.t.into(),
                point.reflectivity.into(),
                point.ring.into(),
                point.ambient.into(),
                point.range.into(),
            ]
            .into()
        }
    }

    unsafe impl PointConvertible<9> for PointA {
        fn layout() -> LayoutDescription {
            LayoutDescription::new(&[
                LayoutField::new("x", "f32", 4),
                LayoutField::new("y", "f32", 4),
                LayoutField::new("z", "f32", 4),
                LayoutField::new("intensity", "f32", 4),
                LayoutField::new("t", "u32", 4),
                LayoutField::new("reflectivity", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("ring", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("ambient", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("range", "u32", 4),
            ])
        }
    }

    impl PointA {
        fn new(x: f32, y: f32, z: f32) -> Self {
            Self {
                x,
                y,
                z,
                intensity: 0.0,
                t: 0,
                reflectivity: 0,
                ring: 0,
                ambient: 0,
                range: 0,
            }
        }
    }

    #[derive(Debug, Clone, Default, PartialEq, Copy)]
    #[repr(C)]
    struct PointB {
        pub x: f32,
        pub y: f32,
        pub z: f32,
        pub t: u32,
    }

    impl PointB {
        fn new(x: f32, y: f32, z: f32) -> Self {
            Self { x, y, z, t: 0 }
        }
    }

    impl From<IPoint<4>> for PointB {
        fn from(point: IPoint<4>) -> Self {
            Self::new(point[0].get(), point[1].get(), point[2].get())
        }
    }

    impl From<PointB> for IPoint<4> {
        fn from(point: PointB) -> Self {
            [
                point.x.into(),
                point.y.into(),
                point.z.into(),
                point.t.into(),
            ]
            .into()
        }
    }

    unsafe impl PointConvertible<4> for PointB {
        fn layout() -> LayoutDescription {
            LayoutDescription::new(&[
                LayoutField::new("x", "f32", 4),
                LayoutField::new("y", "f32", 4),
                LayoutField::new("z", "f32", 4),
                LayoutField::new("t", "u32", 4),
            ])
        }
    }

    #[derive(Debug, Clone, Default, PartialEq, Copy)]
    #[repr(C)]
    struct PointD {
        x: f32,
        y: f32,
        z: f32,
        t: u32,
        ring: u16,
        range: u32,
        signal: u16,
        reflectivity: u16,
        near_ir: u16,
    }

    impl From<IPoint<9>> for PointD {
        fn from(point: IPoint<9>) -> Self {
            Self::new(point[0].get(), point[1].get(), point[2].get())
        }
    }

    impl From<PointD> for IPoint<9> {
        fn from(point: PointD) -> Self {
            [
                point.x.into(),
                point.y.into(),
                point.z.into(),
                point.t.into(),
                point.ring.into(),
                point.range.into(),
                point.signal.into(),
                point.reflectivity.into(),
                point.near_ir.into(),
            ]
            .into()
        }
    }

    unsafe impl PointConvertible<9> for PointD {
        fn layout() -> LayoutDescription {
            LayoutDescription::new(&[
                LayoutField::new("x", "f32", 4),
                LayoutField::new("y", "f32", 4),
                LayoutField::new("z", "f32", 4),
                LayoutField::new("t", "u32", 4),
                LayoutField::new("ring", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("range", "u32", 4),
                LayoutField::new("signal", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("reflectivity", "u16", 2),
                LayoutField::padding(2),
                LayoutField::new("near_ir", "u16", 2),
                LayoutField::padding(2),
            ])
        }
    }

    impl PointD {
        fn new(x: f32, y: f32, z: f32) -> Self {
            Self {
                x,
                y,
                z,
                t: 0,
                ring: 0,
                range: 0,
                signal: 0,
                reflectivity: 0,
                near_ir: 0,
            }
        }
    }

    #[test]
    fn subtype_iterator_fallback() {
        let cloud_a = PointCloud2Msg::try_from_iter(&vec![
            PointA::new(1.0, 2.0, 3.0),
            PointA::new(4.0, 5.0, 6.0),
            PointA::new(7.0, 8.0, 9.0),
        ])
        .unwrap();

        let cloud_c: PointB = cloud_a.clone().try_into_iter().unwrap().next().unwrap();
        assert_eq!(cloud_c, PointB::new(1.0, 2.0, 3.0));

        let cloud_b: Vec<PointB> = cloud_a.try_into_vec().unwrap();
        assert_eq!(cloud_b[0], PointB::new(1.0, 2.0, 3.0));
        assert_eq!(cloud_b[1], PointB::new(4.0, 5.0, 6.0));
        assert_eq!(cloud_b[2], PointB::new(7.0, 8.0, 9.0));
    }
}