38 #include <pcl/filters/extract_indices.h> 44 DiagnosticNodelet(
"OrganizedPassThrough")
51 DiagnosticNodelet::onInit();
55 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
60 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
61 dynamic_reconfigure::Server<Config>::CallbackType
f =
64 srv_->setCallback (f);
84 if (config.filter_field == 0) {
99 pcl::PointIndices::Ptr indices (
new pcl::PointIndices);
102 for (
size_t j = 0; j < pc->height; j++) {
104 size_t idx = i + j * pc->width;
106 indices->indices.push_back(idx);
111 for (
size_t i = 0; i < pc->width; i++) {
113 size_t idx = i + j * pc->width;
115 indices->indices.push_back(idx);
126 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
130 pcl::ExtractIndices<PointT>
ex;
131 ex.setInputCloud(cloud);
132 ex.setIndices(indices);
135 pcl::PointCloud<PointT>
output;
137 sensor_msgs::PointCloud2 ros_output;
139 ros_output.header = msg->header;
148 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
152 stat.
add(
"filter field",
"x");
155 stat.
add(
"filter field",
"y");
169 DiagnosticNodelet::updateDiagnostic(stat);
jsk_topic_tools::Counter filtered_points_counter_
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
jsk_pcl_ros::OrganizedPassThroughConfig Config
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
bool filter_limit_negative_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
void output(int index, double value)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OrganizedPassThrough, nodelet::Nodelet)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual pcl::PointIndices::Ptr filterIndices(const pcl::PointCloud< PointT >::Ptr &pc)
void add(const std::string &key, const T &val)
FilterField filter_field_
bool isPointNaN(const PointT &p)
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)