2 #include <sensor_msgs/PointCloud2.h>
4 #include <pcl/pcl_base.h>
5 #include <pcl/point_types.h>
6 #include <pcl/conversions.h>
7 #include <pcl/filters/extract_indices.h>
17 #include <jsk_topic_tools/connection_based_nodelet.h>
19 #include <dynamic_reconfigure/server.h>
20 #include <jsk_pcl_ros/ResizePointsPublisherConfig.h>
31 typedef jsk_pcl_ros::ResizePointsPublisherConfig
Config;
46 ConnectionBasedNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (
f);
54 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
69 cv::Mat mask = cv_ptr->image;
70 int maskwidth = mask.cols;
71 int maskheight = mask.rows;
73 for (
size_t j = 0; j < maskheight; j++){
74 for (
size_t i = 0;
i < maskwidth;
i++){
75 if (mask.at<uchar>(j,
i) != 0){
80 int surface_per = ((double) cnt) / (maskwidth * maskheight) * 100;
95 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
98 sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter<pcl::PointXYZRGB>,
this,
_1,
_2));
101 sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter<pcl::PointXYZ>,
this,
_1,
_2));
106 sub_ = pnh_->subscribe(
108 &ResizePointsPublisher::filter<pcl::PointXYZRGB>,
this);
111 sub_ = pnh_->subscribe(
113 &ResizePointsPublisher::filter<pcl::PointXYZ>,
this);
135 template<
class T>
void filter (
const sensor_msgs::PointCloud2::ConstPtr &
input) {
136 filter<T>(
input, PCLIndicesMsg::ConstPtr());
139 template<
class T>
void filter (
const sensor_msgs::PointCloud2::ConstPtr &
input,
140 const PCLIndicesMsg::ConstPtr &indices) {
141 pcl::PointCloud<T> pcl_input_cloud, output;
144 std::vector<int> ex_indices;
145 ex_indices.resize(0);
162 std::vector<int> flags;
168 for(
unsigned int i = 0;
i < indices->indices.size();
i++) {
169 flags[indices->indices.at(
i)] = 1;
172 for(
int x = ox;
x <
width;
x += sx) {
174 ex_indices.push_back(
y*
width +
x);
180 for(
int x = ox;
x <
width;
x += sx) {
181 ex_indices.push_back(
y*
width +
x);
185 pcl::ExtractIndices<T> extract;
186 extract.setInputCloud (pcl_input_cloud.makeShared());
187 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
188 extract.setIndices (std::make_shared <std::vector<int> > (ex_indices));
190 extract.setIndices (boost::make_shared <std::vector<int> > (ex_indices));
192 extract.setNegative (
false);
193 extract.filter (output);
195 if (output.points.size() > 0) {
196 sensor_msgs::PointCloud2 ros_out;
198 ros_out.header =
input->header;
199 ros_out.width = (
width - ox)/sx;
200 if((
width - ox)%sx) ros_out.width += 1;
201 ros_out.height = (
height - oy)/sy;
202 if((
height - oy)%sy) ros_out.height += 1;
203 ros_out.row_step = ros_out.point_step * ros_out.width;
204 ros_out.is_dense =
input->is_dense;
207 ros_out.width, ros_out.height, ex_indices.size());
211 input->header.stamp.toSec());
213 ros_out.header.stamp.toSec());