22
22
#include < rclcpp/rclcpp.hpp>
23
23
#include < rerun.hpp>
24
24
25
+ #include < sensor_msgs/point_cloud2_iterator.hpp>
26
+
25
27
#include < cv_bridge/cv_bridge.h>
26
28
27
29
#include < cmath>
@@ -56,25 +58,21 @@ void logPointCloud(
56
58
stream.set_time_seconds (
57
59
" timestamp" , rclcpp::Time (msg->header .stamp .sec , msg->header .stamp .nanosec ).seconds ());
58
60
59
- size_t x_offset{0 }, y_offset{0 }, z_offset{0 };
60
61
bool has_x{false }, has_y{false }, has_z{false };
61
62
for (const auto & field : msg->fields ) {
62
63
if (field.name == " x" ) {
63
- x_offset = field.offset ;
64
64
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
65
65
stream.log (entity, rerun::TextLog (" Only FLOAT32 x field supported" ));
66
66
return ;
67
67
}
68
68
has_x = true ;
69
69
} else if (field.name == " y" ) {
70
- y_offset = field.offset ;
71
70
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
72
71
stream.log (entity, rerun::TextLog (" Only FLOAT32 y field supported" ));
73
72
return ;
74
73
}
75
74
has_y = true ;
76
75
} else if (field.name == " z" ) {
77
- z_offset = field.offset ;
78
76
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
79
77
stream.log (entity, rerun::TextLog (" Only FLOAT32 z field supported" ));
80
78
return ;
@@ -88,28 +86,15 @@ void logPointCloud(
88
86
return ;
89
87
}
90
88
89
+ sensor_msgs::PointCloud2ConstIterator<float > itr_x (*msg, " x" );
90
+ sensor_msgs::PointCloud2ConstIterator<float > itr_y (*msg, " y" );
91
+ sensor_msgs::PointCloud2ConstIterator<float > itr_z (*msg, " z" );
92
+
91
93
std::vector<rerun::Position3D> points (msg->width * msg->height );
92
94
std::vector<float > values (msg->width * msg->height );
93
-
94
- auto & colormap_field = *std::find_if (
95
- msg->fields .cbegin (), msg->fields .cend (),
96
- [&](const auto & field) { return field.name == " z" ; });
97
-
98
- for (size_t i = 0 ; i < msg->height ; ++i) {
99
- for (size_t j = 0 ; j < msg->width ; ++j) {
100
- auto offset = i * msg->row_step + j * msg->point_step ;
101
- rerun::Position3D position;
102
- std::memcpy (&position.xyz .xyz [0 ], &msg->data [offset + x_offset], sizeof (float ));
103
- std::memcpy (&position.xyz .xyz [1 ], &msg->data [offset + y_offset], sizeof (float ));
104
- std::memcpy (&position.xyz .xyz [2 ], &msg->data [offset + z_offset], sizeof (float ));
105
- points.emplace_back (std::move (position));
106
-
107
- float value;
108
- std::memcpy (
109
- &value, &msg->data [i * msg->row_step + j * msg->point_step + colormap_field.offset ],
110
- sizeof (float ));
111
- values.emplace_back (value);
112
- }
95
+ for (; itr_x != itr_x.end (); ++itr_x, ++itr_y, ++itr_z) {
96
+ points.emplace_back (*itr_x, *itr_y, *itr_z);
97
+ values.emplace_back (*itr_z);
113
98
}
114
99
115
100
auto colors = colormap (values);
0 commit comments