Skip to content

Commit 5929125

Browse files
committed
refactor: remove move and memcpy for pointcloud logging
Signed-off-by: ktro2828 <[email protected]>
1 parent d9e45f3 commit 5929125

File tree

1 file changed

+9
-24
lines changed

1 file changed

+9
-24
lines changed

awviz/src/rerun_ros_interface.cpp

+9-24
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222
#include <rclcpp/rclcpp.hpp>
2323
#include <rerun.hpp>
2424

25+
#include <sensor_msgs/point_cloud2_iterator.hpp>
26+
2527
#include <cv_bridge/cv_bridge.h>
2628

2729
#include <cmath>
@@ -56,25 +58,21 @@ void logPointCloud(
5658
stream.set_time_seconds(
5759
"timestamp", rclcpp::Time(msg->header.stamp.sec, msg->header.stamp.nanosec).seconds());
5860

59-
size_t x_offset{0}, y_offset{0}, z_offset{0};
6061
bool has_x{false}, has_y{false}, has_z{false};
6162
for (const auto & field : msg->fields) {
6263
if (field.name == "x") {
63-
x_offset = field.offset;
6464
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
6565
stream.log(entity, rerun::TextLog("Only FLOAT32 x field supported"));
6666
return;
6767
}
6868
has_x = true;
6969
} else if (field.name == "y") {
70-
y_offset = field.offset;
7170
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
7271
stream.log(entity, rerun::TextLog("Only FLOAT32 y field supported"));
7372
return;
7473
}
7574
has_y = true;
7675
} else if (field.name == "z") {
77-
z_offset = field.offset;
7876
if (field.datatype != sensor_msgs::msg::PointField::FLOAT32) {
7977
stream.log(entity, rerun::TextLog("Only FLOAT32 z field supported"));
8078
return;
@@ -88,28 +86,15 @@ void logPointCloud(
8886
return;
8987
}
9088

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+
9193
std::vector<rerun::Position3D> points(msg->width * msg->height);
9294
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);
11398
}
11499

115100
auto colors = colormap(values);

0 commit comments

Comments
 (0)