36 #ifndef SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H
37 #define SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H
54 inline int sizeOfPointField(
int datatype)
67 std::stringstream err;
68 err <<
"PointField of type " <<
datatype <<
" does not exist";
69 throw std::runtime_error(err.str());
87 point_field.
count = count;
89 point_field.
offset = offset;
90 cloud_msg.
fields.push_back(point_field);
93 return offset + point_field.
count * sizeOfPointField(
datatype);
106 inline size_t PointCloud2Modifier::size()
const
108 return cloud_msg_.data.size() / cloud_msg_.point_step;
111 inline void PointCloud2Modifier::reserve(
size_t size)
113 cloud_msg_.data.reserve(size * cloud_msg_.point_step);
116 inline void PointCloud2Modifier::resize(
size_t size)
118 cloud_msg_.data.resize(size * cloud_msg_.point_step);
121 if (cloud_msg_.height == 1) {
122 cloud_msg_.width = size;
123 cloud_msg_.row_step = size * cloud_msg_.point_step;
125 if (cloud_msg_.width == 1)
126 cloud_msg_.height = size;
128 cloud_msg_.height = 1;
129 cloud_msg_.width = size;
130 cloud_msg_.row_step = size * cloud_msg_.point_step;
134 inline void PointCloud2Modifier::clear()
136 cloud_msg_.data.clear();
139 if (cloud_msg_.height == 1)
140 cloud_msg_.row_step = cloud_msg_.width = 0;
142 if (cloud_msg_.width == 1)
143 cloud_msg_.height = 0;
145 cloud_msg_.row_step = cloud_msg_.width = cloud_msg_.height = 0;
166 inline void PointCloud2Modifier::setPointCloud2Fields(
int n_fields, ...)
168 cloud_msg_.fields.clear();
169 cloud_msg_.fields.reserve(n_fields);
171 va_start(vl, n_fields);
173 for (
int i = 0; i < n_fields; ++i) {
175 std::string
name(va_arg(vl,
char*));
176 int count(va_arg(vl,
int));
178 offset = addPointField(cloud_msg_,
name, count,
datatype, offset);
183 cloud_msg_.point_step = offset;
184 cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step;
185 cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step);
198 inline void PointCloud2Modifier::setPointCloud2FieldsByString(
int n_fields, ...)
200 cloud_msg_.fields.clear();
201 cloud_msg_.fields.reserve(n_fields);
203 va_start(vl, n_fields);
205 for (
int i = 0; i < n_fields; ++i) {
208 field_name = std::string(va_arg(vl,
char*));
209 if (field_name ==
"xyz") {
217 if ((field_name ==
"rgb") || (field_name ==
"rgba")) {
221 throw std::runtime_error(
"Field " + field_name +
" does not exist");
226 cloud_msg_.point_step = offset;
227 cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step;
228 cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step);
238 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
239 PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase() : data_char_(0), data_(0), data_end_(0)
247 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
248 PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase(C &cloud_msg,
const std::string &field_name)
250 int offset = set_field(cloud_msg, field_name);
252 data_char_ = &(cloud_msg.data.front()) + offset;
253 data_ =
reinterpret_cast<TT*
>(data_char_);
254 data_end_ =
reinterpret_cast<TT*
>(&(cloud_msg.data.back()) + 1 + offset);
261 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
262 V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator =(
const V<T> &iter)
266 point_step_ = iter.point_step_;
267 data_char_ = iter.data_char_;
269 data_end_ = iter.data_end_;
270 is_bigendian_ = iter.is_bigendian_;
281 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
282 TT& PointCloud2IteratorBase<T, TT, U, C, V>::operator [](
size_t i)
const
290 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
291 TT& PointCloud2IteratorBase<T, TT, U, C, V>::operator *()
const
299 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
300 V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator ++()
302 data_char_ += point_step_;
303 data_ =
reinterpret_cast<TT*
>(data_char_);
304 return *
static_cast<V<T>*
>(
this);
311 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
314 V<T> res = *
static_cast<V<T>*
>(
this);
316 res.data_char_ += i*point_step_;
317 res.data_ =
reinterpret_cast<TT*
>(res.data_char_);
325 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
326 V<T>& PointCloud2IteratorBase<T, TT, U, C, V>::operator +=(
int i)
328 data_char_ += i*point_step_;
329 data_ =
reinterpret_cast<TT*
>(data_char_);
330 return *
static_cast<V<T>*
>(
this);
336 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
339 return iter.data_ != data_;
345 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
346 V<T> PointCloud2IteratorBase<T, TT, U, C, V>::end()
const
348 V<T> res = *
static_cast<const V<T>*
>(
this);
349 res.data_ = data_end_;
358 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
359 int PointCloud2IteratorBase<T, TT, U, C, V>::set_field(
const sensor_msgs::PointCloud2 &cloud_msg,
const std::string &field_name)
364 std::vector<sensor_msgs::PointField>::const_iterator field_iter = cloud_msg.
fields.begin(), field_end =
366 while ((field_iter != field_end) && (field_iter->name != field_name))
369 if (field_iter == field_end) {
371 if ((field_name ==
"r") || (field_name ==
"g") || (field_name ==
"b") || (field_name ==
"a"))
374 field_iter = cloud_msg.
fields.begin();
375 while ((field_iter != field_end) && (field_iter->name !=
"rgb") && (field_iter->name !=
"rgba"))
377 if (field_iter == field_end)
378 throw std::runtime_error(
"Field " + field_name +
" does not exist");
379 if (field_name ==
"r")
382 return field_iter->offset + 1;
384 return field_iter->offset + 2;
386 if (field_name ==
"g")
389 return field_iter->offset + 2;
391 return field_iter->offset + 1;
393 if (field_name ==
"b")
396 return field_iter->offset + 3;
398 return field_iter->offset + 0;
400 if (field_name ==
"a")
403 return field_iter->offset + 0;
405 return field_iter->offset + 3;
408 throw std::runtime_error(
"Field " + field_name +
" does not exist");
411 return field_iter->offset;
417 #endif// SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H