44 #include <sensor_msgs/PointCloud2.h>
45 #include <pcl_msgs/PointIndices.h>
57 pub_cloud_ =
n.advertise<sensor_msgs::PointCloud2>(
"output", 1);
71 #if ROS_VERSION_MINIMUM(1,14,0) // melodic
86 ROS_INFO(
"took %f sec to retrieve result", (end_time - start_time).toSec());
93 for (
size_t i = 0;
i < 1000;
i++) {
95 p.x =
i;
p.y = 0;
p.z = 0;
110 ROS_INFO(
"even_cloud_ %d, odd_cloud_ %d, even_organized_cloud_ %d, odd_organized_cloud_ %d",
126 virtual void evenCallback(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
129 even_cloud_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
133 virtual void oddCallback(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
136 odd_cloud_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
167 EXPECT_EQ(even_cloud_->points.size(), even_indices_msg_.indices.size());
168 for (
size_t i = 0;
i < even_cloud_->points.size();
i++) {
175 EXPECT_EQ(odd_cloud_->points.size(), odd_indices_msg_.indices.size());
176 for (
size_t i = 0;
i < odd_cloud_->points.size();
i++) {
183 EXPECT_EQ(even_organized_cloud_->points.size(), original_cloud_->points.size());
184 size_t non_nan_count = 0;
185 for (
size_t i = 0;
i < even_organized_cloud_->points.size();
i++) {
186 if (!std::isnan(even_organized_cloud_->points[i].x)) {
191 EXPECT_EQ(non_nan_count, even_indices_msg_.indices.size());
196 EXPECT_EQ(odd_organized_cloud_->points.size(), original_cloud_->points.size());
197 size_t non_nan_count = 0;
198 for (
size_t i = 0;
i < odd_organized_cloud_->points.size();
i++) {
199 if (!std::isnan(odd_organized_cloud_->points[
i].x)) {
204 EXPECT_EQ(non_nan_count, odd_indices_msg_.indices.size());
208 int main(
int argc,
char** argv)
211 #if ROS_VERSION_MINIMUM(1,14,0) // melodic