Skip to content

Commit

Permalink
Merge pull request ros-perception#67 from vrabaud/jade-devel
Browse files Browse the repository at this point in the history
remove warnings
  • Loading branch information
tfoote committed May 11, 2015
2 parents dacace2 + 8978810 commit 2a24ff3
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 12 deletions.
4 changes: 2 additions & 2 deletions sensor_msgs/include/sensor_msgs/impl/point_cloud2_iterator.h
Original file line number Diff line number Diff line change
Expand Up @@ -226,11 +226,10 @@ inline void PointCloud2Modifier::setPointCloud2FieldsByString(int n_fields, ...)
cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step;
cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step);
}
}

////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

namespace
namespace impl
{

/**
Expand Down Expand Up @@ -411,6 +410,7 @@ int PointCloud2IteratorBase<T, TT, U, C, V>::set_field(const sensor_msgs::PointC
return field_iter->offset;
}

}
}

#endif// SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H
19 changes: 9 additions & 10 deletions sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
* // 4 is for the number of added fields. Each come in triplet: the name of the PointField,
* // the number of occurences of the type in the PointField, the type of the PointField
* sensor_msgs::PointCloud2Modifier modifier(cloud_msg);
* modifier.setPointCloud2FieldsByString(4, "x", 1, sensor_msgs::PointField::FLOAT32,
* modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
* "y", 1, sensor_msgs::PointField::FLOAT32,
* "z", 1, sensor_msgs::PointField::FLOAT32,
* "rgb", 1, sensor_msgs::PointField::FLOAT32);
Expand All @@ -64,6 +64,8 @@
* // so it is definitely the solution of choice for PointXYZ and PointXYZRGB
* // 2 is for the number of fields to add
* modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
* // You can then reserve / resize as usual
* modifier.resize(100);
* </PRE>
*
* The second set allow you to traverse your PointCloud using an iterator:
Expand Down Expand Up @@ -138,7 +140,7 @@ class PointCloud2Modifier
*
* E.g, you create your PointCloud2 message with XYZ/RGB as follows:
* <PRE>
* setPointCloud2FieldsByString(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
* setPointCloud2Fields(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
* "y", 1, sensor_msgs::PointField::FLOAT32,
* "z", 1, sensor_msgs::PointField::FLOAT32,
* "rgb", 1, sensor_msgs::PointField::FLOAT32);
Expand All @@ -163,9 +165,8 @@ class PointCloud2Modifier
/** A reference to the original sensor_msgs::PointCloud2 that we read */
PointCloud2& cloud_msg_;
};
}

namespace
namespace impl
{
/** Private base class for PointCloud2Iterator and PointCloud2ConstIterator
* T is the type of the value on which the child class will be templated
Expand Down Expand Up @@ -253,8 +254,6 @@ class PointCloud2IteratorBase
};
}

namespace sensor_msgs
{
/**
* \brief Class that can iterate over a PointCloud2
*
Expand All @@ -279,22 +278,22 @@ namespace sensor_msgs
* and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2]
*/
template<typename T>
class PointCloud2Iterator : public PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
class PointCloud2Iterator : public impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, PointCloud2Iterator>
{
public:
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2Iterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
};

/**
* \brief Same as a PointCloud2Iterator but for const data
*/
template<typename T>
class PointCloud2ConstIterator : public PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, PointCloud2ConstIterator>
{
public:
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) :
PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::PointCloud2, sensor_msgs::PointCloud2ConstIterator>::PointCloud2IteratorBase(cloud_msg, field_name) {}
};
}

Expand Down

0 comments on commit 2a24ff3

Please sign in to comment.