54 std::vector<sensor_msgs::PointField>::const_iterator field_iter = cloud.fields.begin(), field_end =
56 bool has_x, has_y, has_z;
57 has_x = has_y = has_z =
false;
58 while (field_iter != field_end) {
59 if ((field_iter->name ==
"x") || (field_iter->name ==
"X"))
61 if ((field_iter->name ==
"y") || (field_iter->name ==
"Y"))
63 if ((field_iter->name ==
"z") || (field_iter->name ==
"Z"))
68 if ((!has_x) || (!has_y) || (!has_z))
69 throw std::runtime_error(
"One of the fields xyz does not exist");
72 pcd_modifier.
resize(points.size());
78 for (point3d_list::const_iterator it = points.begin(); it != points.end(); ++it, ++iter_x, ++iter_y, ++iter_z) {
93 octomapCloud.
reserve(cloud.data.size() / cloud.point_step);
99 for (; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z){
101 if (!std::isnan (*iter_x) && !std::isnan (*iter_y) && !std::isnan (*iter_z))
102 octomapCloud.
push_back(*iter_x, *iter_y, *iter_z);