42 const sensor_msgs::PointCloud2::ConstPtr& normal)
44 if (xyz->width != normal->width || xyz->height != normal->height) {
45 NODELET_ERROR(
"~input and ~normal's width or height does not match");
46 NODELET_ERROR(
"xyz: width=%d, height=%d", xyz->width, xyz->height);
47 NODELET_ERROR(
"normal: width=%d, height=%d", normal->width, normal->height);
50 pcl::PointCloud<pcl::PointXYZRGB> xyz_cloud;
51 pcl::PointCloud<pcl::Normal> normal_cloud;
52 pcl::PointCloud<pcl::PointXYZRGBNormal> concatenated_cloud;
56 concatenated_cloud.points.resize(xyz_cloud.points.size());
57 concatenated_cloud.width = xyz_cloud.width;
58 concatenated_cloud.height = xyz_cloud.height;
59 concatenated_cloud.is_dense = xyz_cloud.is_dense;
61 for (
size_t i = 0;
i < concatenated_cloud.points.size();
i++) {
62 pcl::PointXYZRGBNormal
point;
63 point.x = xyz_cloud.points[
i].x;
64 point.y = xyz_cloud.points[
i].y;
65 point.z = xyz_cloud.points[
i].z;
66 point.rgb = xyz_cloud.points[
i].rgb;
67 point.normal_x = normal_cloud.points[
i].normal_x;
68 point.normal_y = normal_cloud.points[
i].normal_y;
69 point.normal_z = normal_cloud.points[
i].normal_z;
70 point.curvature = normal_cloud.points[
i].curvature;
71 concatenated_cloud.points[
i] =
point;
73 sensor_msgs::PointCloud2 output_cloud;
75 output_cloud.header = xyz->header;
81 ConnectionBasedNodelet::onInit();
82 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
84 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);