TAMSVIZ
Visualization and annotation tool for ROS
pointcloud.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "pointcloud.h"
5 
6 #include <sensor_msgs/point_cloud_conversion.h>
7 
8 #include "../core/document.h"
9 #include "../core/mparser.h"
10 #include "../core/mquery.h"
11 
12 // shouldn't have used eigen
13 void resizeEigenVectorVector3f(std::vector<Eigen::Vector3f> &vector,
14  size_t size) {
15  struct Vec3 {
16  float x, y, z;
17  };
18  ((std::vector<Vec3> *)(&vector))->resize(size);
19 }
20 
21 PointCloudDisplayBase::PointCloudDisplayBase() {
22  _material_renderer->block().flags |= 2; // unlit
23  _material_renderer->block().flags |= 4; // sbgr colors
24  _material->color().r() = 1;
25  _material->color().g() = 1;
26  _material->color().b() = 1;
27 }
28 
29 template <class T>
30 void fetchPointPositionData(size_t point_count, size_t point_step,
31  size_t offset_x, size_t offset_y, size_t offset_z,
32  const std::vector<uint8_t> &buffer,
33  std::vector<Eigen::Vector3f> &positions) {
34  {
35  PROFILER("allocate point positions");
36  resizeEigenVectorVector3f(positions, point_count);
37  }
38 
39  if (point_count == 0) {
40  return;
41  }
42 
43  if (sizeof(T) == 4 && (point_step % 4 == 0) && (offset_x % 4 == 0) &&
44  (offset_y == offset_x + sizeof(T)) &&
45  (offset_z == offset_y + sizeof(T))) {
46  PROFILER("fetch point positions fast");
47  auto *p_buf = reinterpret_cast<const uint32_t *>(buffer.data());
48  auto *p_pos = reinterpret_cast<uint32_t *>(&positions[0].x());
49  auto *p_pos_end = p_pos + point_count * 3;
50  p_buf += offset_x / 4;
51  point_step /= 4;
52  while (p_pos < p_pos_end) {
53  p_pos[0] = p_buf[0];
54  p_pos[1] = p_buf[1];
55  p_pos[2] = p_buf[2];
56  p_buf += point_step;
57  p_pos += 3;
58  }
59  return;
60  }
61 
62  {
63  PROFILER("fetch point positions");
64  auto *p_buf = buffer.data();
65  auto *p_pos = &positions[0].x();
66  for (size_t i = 0; i < point_count; i++) {
67  p_pos[0] = *reinterpret_cast<const T *>(p_buf + offset_x);
68  p_pos[1] = *reinterpret_cast<const T *>(p_buf + offset_y);
69  p_pos[2] = *reinterpret_cast<const T *>(p_buf + offset_z);
70  p_buf += point_step;
71  p_pos += 3;
72  }
73  }
74 }
75 
76 void PointCloudDisplayBase::setPointCloud(
77  const std::shared_ptr<const Message> &message) {
78 
79  PROFILER("set point cloud");
80 
81  if (message) {
82 
83  {
84  PROFILER("extract frame id");
85  static MessageQuery query("header.frame_id");
86  MessageParser parser(message);
87  node()->frame(query(parser).toString());
88  }
89 
90  bool use_point_colors = pointColors();
91  _mesh_renderer = node()->create<MeshRenderer>(
92  std::make_shared<Mesh>([message, use_point_colors](MeshData &mesh) {
93 
94  std::shared_ptr<const sensor_msgs::PointCloud2> cloud;
95  {
96  PROFILER("instantiate point cloud");
97  cloud = message->instantiate<sensor_msgs::PointCloud2>();
98  if (!cloud) {
99  auto cloud1 = message->instantiate<sensor_msgs::PointCloud>();
100  if (cloud1) {
101  auto cloud2 = std::make_shared<sensor_msgs::PointCloud2>();
102  bool ok = sensor_msgs::convertPointCloudToPointCloud2(*cloud1,
103  *cloud2);
104  if (ok) {
105  cloud = cloud2;
106  } else {
107  LOG_ERROR_THROTTLE(1, "failed to parse PointCloud2 message");
108  }
109  }
110  }
111  if (!cloud) {
112  return;
113  }
114  }
115 
116  std::vector<sensor_msgs::PointField> fields;
117  for (auto &field : cloud->fields) {
118  static std::map<uint8_t, size_t> element_sizes = {
119  {sensor_msgs::PointField::INT8, 1},
120  {sensor_msgs::PointField::UINT8, 1},
121  {sensor_msgs::PointField::INT16, 2},
122  {sensor_msgs::PointField::UINT16, 2},
123  {sensor_msgs::PointField::INT32, 4},
124  {sensor_msgs::PointField::UINT32, 4},
125  {sensor_msgs::PointField::FLOAT32, 4},
126  {sensor_msgs::PointField::FLOAT64, 8},
127  };
128  auto it = element_sizes.find(field.datatype);
129  if (it == element_sizes.end()) {
130  LOG_WARN_THROTTLE(1, "unsupported pointcloud data type "
131  << (int)field.datatype);
132  continue;
133  }
134  size_t element_size = it->second;
135  if (size_t(field.offset) + element_size > cloud->point_step) {
136  LOG_WARN_THROTTLE(1, "invalid pointcloud field offset");
137  continue;
138  }
139  fields.push_back(field);
140  }
141 
142  auto findField = [&](const char *name) -> sensor_msgs::PointField * {
143  for (auto &field : fields) {
144  if (field.name == name) {
145  return &field;
146  }
147  }
148  return nullptr;
149  };
150 
151  auto x_field = findField("x");
152  auto y_field = findField("y");
153  auto z_field = findField("z");
154  if (!x_field || !y_field || !z_field) {
155  LOG_ERROR_THROTTLE(1, "no point position attribute");
156  return;
157  }
158 
159  if (x_field->datatype != y_field->datatype ||
160  x_field->datatype != z_field->datatype) {
161  LOG_ERROR_THROTTLE(1, "position datatypes incompatible");
162  return;
163  }
164 
165  size_t point_count = cloud->width * cloud->height;
166  point_count =
167  std::min(point_count, cloud->data.size() / cloud->point_step);
168 
169  switch (x_field->datatype) {
170  case sensor_msgs::PointField::FLOAT32:
171  fetchPointPositionData<float>(
172  point_count, cloud->point_step, x_field->offset,
173  y_field->offset, z_field->offset, cloud->data, mesh.positions);
174  break;
175  case sensor_msgs::PointField::FLOAT64:
176  fetchPointPositionData<double>(
177  point_count, cloud->point_step, x_field->offset,
178  y_field->offset, z_field->offset, cloud->data, mesh.positions);
179  break;
180  default:
181  LOG_ERROR_THROTTLE(1, "unsupported point position datatype");
182  return;
183  }
184 
185  if (use_point_colors) {
186  auto color_field = findField("rgb");
187  if (color_field &&
188  (color_field->datatype == sensor_msgs::PointField::FLOAT32 ||
189  color_field->datatype == sensor_msgs::PointField::INT32 ||
190  color_field->datatype == sensor_msgs::PointField::UINT32)) {
191  {
192  PROFILER("allocate point colors");
193  mesh.colors8.resize(point_count);
194  }
195  {
196  PROFILER("convert point colors");
197  size_t point_step = cloud->point_step;
198  size_t field_offset = color_field->offset;
199  auto *buffer_pointer = cloud->data.data() + field_offset;
200  auto *color_begin = mesh.colors8.data();
201  auto *color_end = (color_begin + point_count);
202  for (auto *color_pointer = color_begin;
203  color_pointer < color_end; color_pointer++) {
204  uint32_t color =
205  *reinterpret_cast<const uint32_t *>(buffer_pointer);
206  *color_pointer = color;
207  buffer_pointer += point_step;
208  }
209  }
210  }
211  }
212 
213  }),
214  _material_renderer);
215 
216  RenderOptions options;
217  options.primitive_type = GL_POINTS;
218  options.point_size = pointSize();
219  _mesh_renderer->options(options);
220 
221  } else {
222 
223  _mesh_renderer.reset();
224  }
225 }
226 
227 void PointCloudDisplay::renderSync(const RenderSyncContext &context) {
228  {
229  PROFILER("pointcloud sync");
230  std::shared_ptr<const Message> message;
231  {
232  PROFILER("fetch message");
233  message = topic().subscriber()->topic()->message();
234  }
235  if (_watcher.changed(message, pointColors())) {
236  setPointCloud(message);
237  }
238  }
239  {
240  PROFILER("pointcloud base");
241  PointCloudDisplayBase::renderSync(context);
242  }
243 }
244 
245 void PointCloud2Display::renderSync(const RenderSyncContext &context) {
246  {
247  PROFILER("pointcloud sync");
248  std::shared_ptr<const Message> message;
249  {
250  PROFILER("fetch message");
251  message = topic().subscriber()->topic()->message();
252  }
253  if (_watcher.changed(message, pointColors())) {
254  setPointCloud(message);
255  }
256  }
257  {
258  PROFILER("pointcloud base");
259  PointCloudDisplayBase::renderSync(context);
260  }
261 }
Definition: mesh.h:11