Skip to content

Commit a7ce032

Browse files
authored
Merge pull request ros2#42 from ros2/uncrustify_master
update style to match latest uncrustify
2 parents db5b97b + 6fb9323 commit a7ce032

File tree

2 files changed

+35
-38
lines changed

2 files changed

+35
-38
lines changed

sensor_msgs/include/sensor_msgs/impl/point_cloud2_iterator.hpp

Lines changed: 14 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,8 @@ inline int sizeOfPointField(int datatype)
8484
* @param offset the offset of that element
8585
* @return the offset of the next PointField that will be added to the PointCloud2
8686
*/
87-
inline int addPointField(sensor_msgs::msg::PointCloud2 & cloud_msg,
87+
inline int addPointField(
88+
sensor_msgs::msg::PointCloud2 & cloud_msg,
8889
const std::string & name, int count, int datatype,
8990
int offset)
9091
{
@@ -263,10 +264,9 @@ PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase()
263264
* @param cloud_msg_ The PointCloud2 to iterate upon
264265
* @param field_name The field to iterate upon
265266
*/
266-
template<typename T, typename TT, typename U, typename C,
267-
template<typename> class V>
268-
PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase(C & cloud_msg,
269-
const std::string & field_name)
267+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
268+
PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase(
269+
C & cloud_msg, const std::string & field_name)
270270
{
271271
int offset = set_field(cloud_msg, field_name);
272272

@@ -279,8 +279,7 @@ PointCloud2IteratorBase<T, TT, U, C, V>::PointCloud2IteratorBase(C & cloud_msg,
279279
* @param iter the iterator to copy data from
280280
* @return a reference to *this
281281
*/
282-
template<typename T, typename TT, typename U, typename C,
283-
template<typename> class V>
282+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
284283
V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator=(const V<T> & iter)
285284
{
286285
if (this != &iter) {
@@ -299,8 +298,7 @@ V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator=(const V<T> & iter)
299298
* @param i
300299
* @return a reference to the i^th value from the current position
301300
*/
302-
template<typename T, typename TT, typename U, typename C,
303-
template<typename> class V>
301+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
304302
TT & PointCloud2IteratorBase<T, TT, U, C, V>::operator[](size_t i) const
305303
{
306304
return *(data_ + i);
@@ -309,8 +307,7 @@ TT & PointCloud2IteratorBase<T, TT, U, C, V>::operator[](size_t i) const
309307
/** Dereference the iterator. Equivalent to accessing it through [0]
310308
* @return the value to which the iterator is pointing
311309
*/
312-
template<typename T, typename TT, typename U, typename C,
313-
template<typename> class V>
310+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
314311
TT & PointCloud2IteratorBase<T, TT, U, C, V>::operator*() const
315312
{
316313
return *data_;
@@ -319,8 +316,7 @@ TT & PointCloud2IteratorBase<T, TT, U, C, V>::operator*() const
319316
/** Increase the iterator to the next element
320317
* @return a reference to the updated iterator
321318
*/
322-
template<typename T, typename TT, typename U, typename C,
323-
template<typename> class V>
319+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
324320
V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator++()
325321
{
326322
data_char_ += point_step_;
@@ -332,8 +328,7 @@ V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator++()
332328
* @param i the amount to increase the iterator by
333329
* @return an iterator with an increased position
334330
*/
335-
template<typename T, typename TT, typename U, typename C,
336-
template<typename> class V>
331+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
337332
V<T> PointCloud2IteratorBase<T, TT, U, C, V>::operator+(int i)
338333
{
339334
V<T> res = *static_cast<V<T> *>(this);
@@ -347,8 +342,7 @@ V<T> PointCloud2IteratorBase<T, TT, U, C, V>::operator+(int i)
347342
/** Increase the iterator by a certain amount
348343
* @return a reference to the updated iterator
349344
*/
350-
template<typename T, typename TT, typename U, typename C,
351-
template<typename> class V>
345+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
352346
V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator+=(int i)
353347
{
354348
data_char_ += i * point_step_;
@@ -359,8 +353,7 @@ V<T> & PointCloud2IteratorBase<T, TT, U, C, V>::operator+=(int i)
359353
/** Compare to another iterator
360354
* @return whether the current iterator points to a different address than the other one
361355
*/
362-
template<typename T, typename TT, typename U, typename C,
363-
template<typename> class V>
356+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
364357
bool PointCloud2IteratorBase<T, TT, U, C, V>::operator!=(const V<T> & iter) const
365358
{
366359
return iter.data_ != data_;
@@ -369,8 +362,7 @@ bool PointCloud2IteratorBase<T, TT, U, C, V>::operator!=(const V<T> & iter) cons
369362
/** Return the end iterator
370363
* @return the end iterator (useful when performing normal iterator processing with ++)
371364
*/
372-
template<typename T, typename TT, typename U, typename C,
373-
template<typename> class V>
365+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
374366
V<T> PointCloud2IteratorBase<T, TT, U, C, V>::end() const
375367
{
376368
V<T> res = *static_cast<const V<T> *>(this);
@@ -383,8 +375,7 @@ V<T> PointCloud2IteratorBase<T, TT, U, C, V>::end() const
383375
* @param field_name the name of the field to iterate upon
384376
* @return the offset at which the field is found
385377
*/
386-
template<typename T, typename TT, typename U, typename C,
387-
template<typename> class V>
378+
template<typename T, typename TT, typename U, typename C, template<typename> class V>
388379
int PointCloud2IteratorBase<T, TT, U, C, V>::set_field(
389380
const sensor_msgs::msg::PointCloud2 & cloud_msg, const std::string & field_name)
390381
{

sensor_msgs/include/sensor_msgs/point_cloud2_iterator.hpp

Lines changed: 21 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -280,33 +280,39 @@ class PointCloud2IteratorBase
280280
* and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2]
281281
*/
282282
template<typename T>
283-
class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T,
284-
unsigned char, sensor_msgs::msg::PointCloud2, PointCloud2Iterator>
283+
class PointCloud2Iterator
284+
: public impl::PointCloud2IteratorBase<
285+
T, T, unsigned char, sensor_msgs::msg::PointCloud2, PointCloud2Iterator>
285286
{
286287
public:
287-
PointCloud2Iterator(sensor_msgs::msg::PointCloud2 & cloud_msg,
288+
PointCloud2Iterator(
289+
sensor_msgs::msg::PointCloud2 & cloud_msg,
288290
const std::string & field_name)
289-
: impl::PointCloud2IteratorBase<T, T, unsigned char,
290-
sensor_msgs::msg::PointCloud2,
291-
sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg,
292-
field_name) {}
291+
: impl::PointCloud2IteratorBase<
292+
T, T, unsigned char,
293+
sensor_msgs::msg::PointCloud2,
294+
sensor_msgs::PointCloud2Iterator
295+
>::PointCloud2IteratorBase(cloud_msg, field_name) {}
293296
};
294297

295298
/**
296299
* \brief Same as a PointCloud2Iterator but for const data
297300
*/
298301
template<typename T>
299-
class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T,
300-
const T, const unsigned char, const sensor_msgs::msg::PointCloud2,
301-
PointCloud2ConstIterator>
302+
class PointCloud2ConstIterator
303+
: public impl::PointCloud2IteratorBase<
304+
T, const T, const unsigned char, const sensor_msgs::msg::PointCloud2,
305+
PointCloud2ConstIterator>
302306
{
303307
public:
304-
PointCloud2ConstIterator(const sensor_msgs::msg::PointCloud2 & cloud_msg,
308+
PointCloud2ConstIterator(
309+
const sensor_msgs::msg::PointCloud2 & cloud_msg,
305310
const std::string & field_name)
306-
: impl::PointCloud2IteratorBase<T, const T, const unsigned char,
307-
const sensor_msgs::msg::PointCloud2,
308-
sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg,
309-
field_name) {}
311+
: impl::PointCloud2IteratorBase<
312+
T, const T, const unsigned char,
313+
const sensor_msgs::msg::PointCloud2,
314+
sensor_msgs::PointCloud2ConstIterator
315+
>::PointCloud2IteratorBase(cloud_msg, field_name) {}
310316
};
311317
} // namespace sensor_msgs
312318

0 commit comments

Comments
 (0)