37 #include <jsk_topic_tools/diagnostic_utils.h>
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);
125 vital_checker_->poke();
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;
141 diagnostic_updater_->update();
147 if (vital_checker_->isAlive()) {
148 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
152 stat.
add(
"filter field",
"x");
155 stat.
add(
"filter field",
"y");
159 jsk_topic_tools::addDiagnosticBooleanStat(
"keep organized",
162 jsk_topic_tools::addDiagnosticBooleanStat(
"remove_nan",
165 jsk_topic_tools::addDiagnosticBooleanStat(
"filter_limit_negative",
169 DiagnosticNodelet::updateDiagnostic(stat);