39 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl/filters/voxel_grid.h>
42 #include <pcl/io/vtk_lib_io.h>
43 #include <pcl/point_cloud.h>
44 #include <pcl/point_types.h>
49 pcl::PointXYZ
operator-(
const pcl::PointXYZ& a,
const pcl::PointXYZ& b)
57 pcl::PointXYZ
operator+(
const pcl::PointXYZ& a,
const pcl::PointXYZ& b)
65 pcl::PointXYZ
operator*(
const pcl::PointXYZ& a,
const float& b)
74 std::vector<std::string>
split(
const std::string& input,
char delimiter)
76 std::istringstream stream(input);
79 std::vector<std::string> result;
80 while (std::getline(stream, field, delimiter))
82 result.push_back(field);
96 pub_cloud_ = neonavigation_common::compat::advertise<sensor_msgs::PointCloud2>(
98 pnh_,
"cloud", 1,
true);
102 if (
file_.compare(
"") == 0)
136 sensor_msgs::PointCloud2
convertObj(
const std::vector<std::string>& files)
138 sensor_msgs::PointCloud2 pc_msg;
139 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh());
140 pcl::PointCloud<pcl::PointXYZ>::Ptr pc(
new pcl::PointCloud<pcl::PointXYZ>());
141 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_rs(
new pcl::PointCloud<pcl::PointXYZ>());
145 pc_rs->points.reserve(500000);
146 for (
auto& file : files)
148 auto ext = file.substr(file.find_last_of(
".") + 1);
158 for (
auto& p : pc->points)
164 pc_rs->points.push_back(p);
167 else if (ext ==
"obj")
169 if (pcl::io::loadPolygonFileOBJ(file, *mesh) == -1)
176 pcl::fromPCLPointCloud2(mesh->cloud, *pc);
177 pc_rs->header = pc->header;
178 for (
auto& p : pc->points)
185 std::uniform_real_distribution<float> ud(0.0, 1.0);
186 for (
auto& poly : mesh->polygons)
188 if (poly.vertices.size() != 3)
190 ROS_ERROR(
"Input mesh mush be triangle");
194 auto& p0 = pc->points[poly.vertices[0]];
195 auto& p1 = pc->points[poly.vertices[1]];
196 auto& p2 = pc->points[poly.vertices[2]];
203 std::pow(a.y * b.z - a.z * b.y, 2) +
204 std::pow(a.z * b.x - a.x * b.z, 2) +
205 std::pow(a.x * b.y - a.y * b.x, 2));
210 for (
int i = 0; i < num; i++)
219 pcl::PointXYZ p = p0 + (a * r0 + b * r1) + offset;
220 pc_rs->points.push_back(p);
225 pc_rs->width = pc_rs->points.size();
227 pc_rs->is_dense =
true;
230 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_ds(
new pcl::PointCloud<pcl::PointXYZ>);
231 pcl::VoxelGrid<pcl::PointXYZ> ds;
232 ds.setInputCloud(pc_rs);
239 ROS_INFO(
"pointcloud (%d points) has been generated from %d verticles",
246 int main(
int argc,
char** argv)
248 ros::init(argc, argv,
"obj_to_pointcloud");