35 #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H 36 #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H 178 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
196 V<T>& operator =(
const V<T>& iter);
203 TT& operator [](
size_t i)
const;
281 class PointCloud2Iterator :
public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
292 class PointCloud2ConstIterator :
public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
302 #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
Same as a PointCloud2Iterator but for const data.
bool operator!=(failed, failed)
void reserve(size_t size)
ImVec4 operator*(const ImVec4 &color, float t)
PointCloud2Modifier(PointCloud2 &cloud_msg)
Default constructor.
GLsizei const GLchar *const * string
void setPointCloud2Fields(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
ImVec4 operator+(const ImVec4 &c, float v)
Tools for manipulating sensor_msgs.
Class that can iterate over a PointCloud2.
Enables modifying a sensor_msgs::PointCloud2 like a container.
auto operator+=(std::string &lhs, StringRef const &sr) -> std::string &
void clear()
remove all T's from the original sensor_msgs::PointCloud2
void setPointCloud2FieldsByString(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
boost::iterators::detail::postfix_increment_result< I, V, R, TC >::type operator++(iterator_facade< I, V, TC, R, D > &i, int)