resize_points_publisher_nodelet.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <sensor_msgs/PointCloud2.h>
3 
4 #include <pcl/pcl_base.h>
5 #include <pcl/point_types.h>
6 #include <pcl/conversions.h>
7 #include <pcl/filters/extract_indices.h>
8 
9 #include <pcl_ros/pcl_nodelet.h>
11 
15 
17 #include <jsk_topic_tools/connection_based_nodelet.h>
18 
19 #include <dynamic_reconfigure/server.h>
20 #include <jsk_pcl_ros/ResizePointsPublisherConfig.h>
21 
22 #include <cv_bridge/cv_bridge.h>
24 
25 namespace jsk_pcl_ros
26 {
27  class ResizePointsPublisher : public jsk_topic_tools::ConnectionBasedNodelet
28  {
29  typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2,
31  typedef jsk_pcl_ros::ResizePointsPublisherConfig Config;
32 
33  private:
45  void onInit () {
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 =
51  boost::bind (
53  srv_->setCallback (f);
54  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
55  resizedmask_sub_ = pnh_->subscribe("input/mask", 1, &ResizePointsPublisher::resizedmaskCallback, this);
56  onInitPostProcess();
57  }
58 
59  void configCallback(Config &config, uint32_t level) {
60  boost::mutex::scoped_lock lock(mutex_);
61  step_x_ = config.step_x;
62  step_y_ = config.step_y;
63  }
64 
65  void resizedmaskCallback (const sensor_msgs::Image::ConstPtr& msg) {
66  boost::mutex::scoped_lock lock(mutex_);
69  cv::Mat mask = cv_ptr->image;
70  int maskwidth = mask.cols;
71  int maskheight = mask.rows;
72  int cnt = 0;
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){
76  cnt++;
77  }
78  }
79  }
80  int surface_per = ((double) cnt) / (maskwidth * maskheight) * 100;
81  // step_x_ = surface_per /10;
82  step_x_ = sqrt(surface_per);
83  if (step_x_ < 1) {
84  step_x_ = 1;
85  }
86  step_y_ = step_x_;
87  }
88 
89  void subscribe()
90  {
91 
92  if (use_indices_) {
93  sub_input_.subscribe(*pnh_, "input", 1);
94  sub_indices_.subscribe(*pnh_, "indices", 1);
95  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
96  sync_->connectInput(sub_input_, sub_indices_);
97  if (!not_use_rgb_) {
98  sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter<pcl::PointXYZRGB>, this, _1, _2));
99  }
100  else {
101  sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter<pcl::PointXYZ>, this, _1, _2));
102  }
103  }
104  else {
105  if (!not_use_rgb_) {
106  sub_ = pnh_->subscribe(
107  "input", 1,
108  &ResizePointsPublisher::filter<pcl::PointXYZRGB>, this);
109  }
110  else {
111  sub_ = pnh_->subscribe(
112  "input", 1,
113  &ResizePointsPublisher::filter<pcl::PointXYZ>, this);
114  }
115  }
116  }
117 
118  void unsubscribe()
119  {
120  if (use_indices_) {
123  }
124  else {
125  sub_.shutdown();
126  }
127  }
128 
130  if (use_indices_) {
131  sync_.reset();
132  }
133  }
134 
135  template<class T> void filter (const sensor_msgs::PointCloud2::ConstPtr &input) {
136  filter<T>(input, PCLIndicesMsg::ConstPtr());
137  }
138 
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;
142  fromROSMsg(*input, pcl_input_cloud);
143  boost::mutex::scoped_lock lock (mutex_);
144  std::vector<int> ex_indices;
145  ex_indices.resize(0);
146 
147  int width = input->width;
148  int height = input->height;
149  int ox, oy, sx, sy;
150 
151  sx = step_x_;
152  ox = sx/2;
153  if(height == 1) {
154  sy = 1;
155  oy = 0;
156  } else {
157  sy = step_y_;
158  oy = sy/2;
159  }
160 
161  if (indices) {
162  std::vector<int> flags;
163  flags.resize(width*height);
164 
165  //std::vector<int>::iterator it;
166  //for(it = indices->begin(); it != indices->end(); it++)
167  //flags[*it] = 1;
168  for(unsigned int i = 0; i < indices->indices.size(); i++) {
169  flags[indices->indices.at(i)] = 1;
170  }
171  for(int y = oy; y < height; y += sy) {
172  for(int x = ox; x < width; x += sx) {
173  if (flags[y*width + x] == 1) {
174  ex_indices.push_back(y*width + x); // just use points in indices
175  }
176  }
177  }
178  } else {
179  for(int y = oy; y < height; y += sy) {
180  for(int x = ox; x < width; x += sx) {
181  ex_indices.push_back(y*width + x);
182  }
183  }
184  }
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));
189 #else
190  extract.setIndices (boost::make_shared <std::vector<int> > (ex_indices));
191 #endif
192  extract.setNegative (false);
193  extract.filter (output);
194 
195  if (output.points.size() > 0) {
196  sensor_msgs::PointCloud2 ros_out;
197  toROSMsg(output, 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;
205 #if DEBUG
206  NODELET_INFO("%dx%d (%d %d)(%d %d) -> %dx%d %d", width,height, ox, oy, sx, sy,
207  ros_out.width, ros_out.height, ex_indices.size());
208 #endif
209  pub_.publish(ros_out);
210  NODELET_DEBUG("%s:: input header stamp is [%f]", getName().c_str(),
211  input->header.stamp.toSec());
212  NODELET_DEBUG("%s:: output header stamp is [%f]", getName().c_str(),
213  ros_out.header.stamp.toSec());
214  }
215 
216  }
217 
218  };
219 }
220 
jsk_pcl_ros::ResizePointsPublisher::resizedmask_sub_
ros::Subscriber resizedmask_sub_
Definition: resize_points_publisher_nodelet.cpp:39
jsk_pcl_ros::ResizePointsPublisher::mutex_
boost::mutex mutex_
Definition: resize_points_publisher_nodelet.cpp:43
DEBUG
#define DEBUG(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
ros::Publisher
_2
boost::arg< 2 > _2
image_encodings.h
boost::shared_ptr
i
int i
jsk_pcl_ros::ResizePointsPublisher::unsubscribe
void unsubscribe()
Definition: resize_points_publisher_nodelet.cpp:118
ros.h
jsk_pcl_ros::ResizePointsPublisher::filter
void filter(const sensor_msgs::PointCloud2::ConstPtr &input)
Definition: resize_points_publisher_nodelet.cpp:135
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
jsk_pcl_ros::ResizePointsPublisher::onInit
void onInit()
Definition: resize_points_publisher_nodelet.cpp:45
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros::ResizePointsPublisher::filter
void filter(const sensor_msgs::PointCloud2::ConstPtr &input, const PCLIndicesMsg::ConstPtr &indices)
Definition: resize_points_publisher_nodelet.cpp:139
ros::Subscriber::shutdown
void shutdown()
time_synchronizer.h
attention_pose_set.x
x
Definition: attention_pose_set.py:18
fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::ResizePointsPublisher::use_indices_
bool use_indices_
Definition: resize_points_publisher_nodelet.cpp:44
jsk_pcl_ros::ResizePointsPublisher::sub_indices_
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
Definition: resize_points_publisher_nodelet.cpp:36
jsk_pcl_ros::ResizePointsPublisher
Definition: resize_points_publisher_nodelet.cpp:27
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::ResizePointsPublisher::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, PCLIndicesMsg > SyncPolicy
Definition: resize_points_publisher_nodelet.cpp:30
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::ResizePointsPublisher::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: resize_points_publisher_nodelet.cpp:35
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::ResizePointsPublisher::not_use_rgb_
bool not_use_rgb_
Definition: resize_points_publisher_nodelet.cpp:42
jsk_pcl_ros::ResizePointsPublisher::pub_
ros::Publisher pub_
Definition: resize_points_publisher_nodelet.cpp:41
class_list_macros.h
pcl_nodelet.h
jsk_pcl_ros::ResizePointsPublisher::step_x_
int step_x_
Definition: resize_points_publisher_nodelet.cpp:34
jsk_pcl_ros::ResizePointsPublisher::step_y_
int step_y_
Definition: resize_points_publisher_nodelet.cpp:34
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::ResizePointsPublisher::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: resize_points_publisher_nodelet.cpp:37
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
subscriber.h
jsk_pcl_ros::ResizePointsPublisher::Config
jsk_pcl_ros::ResizePointsPublisherConfig Config
Definition: resize_points_publisher_nodelet.cpp:31
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ResizePointsPublisher, nodelet::Nodelet)
_1
boost::arg< 1 > _1
jsk_pcl_ros::ResizePointsPublisher::~ResizePointsPublisher
~ResizePointsPublisher()
Definition: resize_points_publisher_nodelet.cpp:129
jsk_pcl_ros::ResizePointsPublisher::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: resize_points_publisher_nodelet.cpp:40
pcl_conversion_util.h
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
nodelet::Nodelet
jsk_pcl_ros::ResizePointsPublisher::resizedmaskCallback
void resizedmaskCallback(const sensor_msgs::Image::ConstPtr &msg)
Definition: resize_points_publisher_nodelet.cpp:65
sqrt
double sqrt()
width
width
jsk_pcl_ros::ResizePointsPublisher::sub_
ros::Subscriber sub_
Definition: resize_points_publisher_nodelet.cpp:38
sensor_msgs::image_encodings::MONO8
const std::string MONO8
cv_bridge.h
dump_depth_error.f
f
Definition: dump_depth_error.py:39
synchronizer.h
toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::ResizePointsPublisher::configCallback
void configCallback(Config &config, uint32_t level)
Definition: resize_points_publisher_nodelet.cpp:59
attention_pose_set.y
y
Definition: attention_pose_set.py:19
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
height
height
config
config
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
ros::Subscriber
jsk_pcl_ros::ResizePointsPublisher::subscribe
void subscribe()
Definition: resize_points_publisher_nodelet.cpp:89
NODELET_DEBUG
#define NODELET_DEBUG(...)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:12