36 #define BOOST_PARAMETER_MAX_ARITY 7 42 #include <pcl/filters/extract_indices.h> 49 DiagnosticNodelet::onInit();
50 pub_ = advertise<PCLIndicesMsg>(
63 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
77 const sensor_msgs::CameraInfo::ConstPtr& info_ms)
84 const sensor_msgs::Image::ConstPtr& mask_msg)
93 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
94 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
100 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud 101 (
new pcl::PointCloud<pcl::PointXYZRGB>);
104 indices.header = cloud_msg->header;
105 pcl::ExtractIndices<pcl::PointXYZRGB> extract;
106 extract.setInputCloud(cloud);
107 for (
size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
108 pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
109 pcl::IndicesPtr vindices;
110 vindices.reset (
new std::vector<int> (indices_input->cluster_indices[i].indices));
111 extract.setIndices(vindices);
112 extract.filter(*segmented_cloud);
113 bool in_mask =
false;
114 for (
size_t j = 0; j < segmented_cloud->points.size(); j++) {
115 pcl::PointXYZRGB
p = segmented_cloud->points[j];
128 for(
size_t j=0; j < vindices->size(); j++)
130 indices.indices.push_back((*vindices)[j]);
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MaskImageClusterFilter, nodelet::Nodelet)
virtual void unsubscribe()
void publish(const boost::shared_ptr< M > &message) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Subscriber sub_image_
virtual void concat(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
virtual void imageCalback(const sensor_msgs::Image::ConstPtr &mask_msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
sensor_msgs::CameraInfo::ConstPtr camera_info_
ros::Subscriber sub_info_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual void infoCalback(const sensor_msgs::CameraInfo::ConstPtr &info_ms)
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
pcl::PointIndices PCLIndicesMsg