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> 19 #include <dynamic_reconfigure/server.h> 20 #include <jsk_pcl_ros/ResizePointsPublisherConfig.h> 31 typedef jsk_pcl_ros::ResizePointsPublisherConfig
Config;
46 ConnectionBasedNodelet::onInit();
47 pnh_->param(
"use_indices", use_indices_,
false);
48 pnh_->param(
"not_use_rgb", not_use_rgb_,
false);
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);
60 boost::mutex::scoped_lock
lock(mutex_);
61 step_x_ = config.step_x;
62 step_y_ = config.step_y;
66 boost::mutex::scoped_lock
lock(mutex_);
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;
82 step_x_ =
sqrt(surface_per);
95 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
96 sync_->connectInput(sub_input_, sub_indices_);
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);
131 template<
class T>
void filter (
const sensor_msgs::PointCloud2::ConstPtr &input) {
132 filter<T>(input, PCLIndicesMsg::ConstPtr());
135 template<
class T>
void filter (
const sensor_msgs::PointCloud2::ConstPtr &input,
136 const PCLIndicesMsg::ConstPtr &indices) {
137 pcl::PointCloud<T> pcl_input_cloud,
output;
138 fromROSMsg(*input, pcl_input_cloud);
139 boost::mutex::scoped_lock
lock (mutex_);
140 std::vector<int> ex_indices;
141 ex_indices.resize(0);
143 int width = input->width;
144 int height = input->height;
158 std::vector<int> flags;
159 flags.resize(width*height);
164 for(
unsigned int i = 0; i < indices->indices.size(); i++) {
165 flags[indices->indices.at(i)] = 1;
167 for(
int y = oy;
y < height;
y += sy) {
168 for(
int x = ox;
x < width;
x += sx) {
169 if (flags[
y*width +
x] == 1) {
170 ex_indices.push_back(
y*width +
x);
175 for(
int y = oy;
y < height;
y += sy) {
176 for(
int x = ox;
x < width;
x += sx) {
177 ex_indices.push_back(
y*width +
x);
181 pcl::ExtractIndices<T> extract;
182 extract.setInputCloud (pcl_input_cloud.makeShared());
183 extract.setIndices (boost::make_shared <std::vector<int> > (ex_indices));
184 extract.setNegative (
false);
185 extract.filter (output);
187 if (output.points.size() > 0) {
188 sensor_msgs::PointCloud2 ros_out;
189 toROSMsg(output, ros_out);
190 ros_out.header = input->header;
191 ros_out.width = (width - ox)/sx;
192 if((width - ox)%sx) ros_out.width += 1;
193 ros_out.height = (height - oy)/sy;
194 if((height - oy)%sy) ros_out.height += 1;
195 ros_out.row_step = ros_out.point_step * ros_out.width;
196 ros_out.is_dense = input->is_dense;
198 NODELET_INFO(
"%dx%d (%d %d)(%d %d) -> %dx%d %d", width,height, ox, oy, sx, sy,
199 ros_out.width, ros_out.height, ex_indices.size());
203 input->header.stamp.toSec());
205 ros_out.header.stamp.toSec());
jsk_pcl_ros::ResizePointsPublisherConfig Config
void publish(const boost::shared_ptr< M > &message) const
const std::string & getName() const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void filter(const sensor_msgs::PointCloud2::ConstPtr &input, const PCLIndicesMsg::ConstPtr &indices)
void output(int index, double value)
void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void filter(const sensor_msgs::PointCloud2::ConstPtr &input)
boost::mutex mutex
global mutex.
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, PCLIndicesMsg > SyncPolicy
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
#define NODELET_INFO(...)
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)
ros::Subscriber resizedmask_sub_
pcl::PointIndices PCLIndicesMsg
#define NODELET_DEBUG(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ResizePointsPublisher, nodelet::Nodelet)
void resizedmaskCallback(const sensor_msgs::Image::ConstPtr &msg)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_