Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "jsk_pcl_ros_utils/normal_concatenater.h"
00036 #include <pluginlib/class_list_macros.h>
00037
00038 namespace jsk_pcl_ros_utils
00039 {
00040
00041 void NormalConcatenater::concatenate(const sensor_msgs::PointCloud2::ConstPtr& xyz,
00042 const sensor_msgs::PointCloud2::ConstPtr& normal)
00043 {
00044 if (xyz->width != normal->width || xyz->height != normal->height) {
00045 NODELET_ERROR("~input and ~normal's width or height does not match");
00046 NODELET_ERROR("xyz: width=%d, height=%d", xyz->width, xyz->height);
00047 NODELET_ERROR("normal: width=%d, height=%d", normal->width, normal->height);
00048 return;
00049 }
00050 pcl::PointCloud<pcl::PointXYZRGB> xyz_cloud;
00051 pcl::PointCloud<pcl::Normal> normal_cloud;
00052 pcl::PointCloud<pcl::PointXYZRGBNormal> concatenated_cloud;
00053 pcl::fromROSMsg(*xyz, xyz_cloud);
00054 pcl::fromROSMsg(*normal, normal_cloud);
00055
00056 concatenated_cloud.points.resize(xyz_cloud.points.size());
00057 concatenated_cloud.width = xyz_cloud.width;
00058 concatenated_cloud.height = xyz_cloud.height;
00059 concatenated_cloud.is_dense = xyz_cloud.is_dense;
00060
00061 for (size_t i = 0; i < concatenated_cloud.points.size(); i++) {
00062 pcl::PointXYZRGBNormal point;
00063 point.x = xyz_cloud.points[i].x;
00064 point.y = xyz_cloud.points[i].y;
00065 point.z = xyz_cloud.points[i].z;
00066 point.rgb = xyz_cloud.points[i].rgb;
00067 point.normal_x = normal_cloud.points[i].normal_x;
00068 point.normal_y = normal_cloud.points[i].normal_y;
00069 point.normal_z = normal_cloud.points[i].normal_z;
00070 point.curvature = normal_cloud.points[i].curvature;
00071 concatenated_cloud.points[i] = point;
00072 }
00073 sensor_msgs::PointCloud2 output_cloud;
00074 pcl::toROSMsg(concatenated_cloud, output_cloud);
00075 output_cloud.header = xyz->header;
00076 pub_.publish(output_cloud);
00077 }
00078
00079 void NormalConcatenater::onInit()
00080 {
00081 ConnectionBasedNodelet::onInit();
00082 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00083 pnh_->param("use_async", use_async_, false);
00084 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00085 if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
00086 maximum_queue_size_ = 100;
00087 }
00088 }
00089
00090 void NormalConcatenater::subscribe()
00091 {
00092 sub_xyz_.subscribe(*pnh_, "input", 1);
00093 sub_normal_.subscribe(*pnh_, "normal", 1);
00094 if (use_async_) {
00095 async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
00096 async_->connectInput(sub_xyz_, sub_normal_);
00097 async_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
00098 }
00099 else {
00100 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
00101 sync_->connectInput(sub_xyz_, sub_normal_);
00102 sync_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2));
00103 }
00104 }
00105
00106 void NormalConcatenater::unsubscribe()
00107 {
00108 sub_xyz_.unsubscribe();
00109 sub_normal_.unsubscribe();
00110 }
00111
00112 }
00113
00114 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::NormalConcatenater, nodelet::Nodelet);
00115