42 ConnectionBasedNodelet::onInit();
47 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
48 dynamic_reconfigure::Server<Config>::CallbackType
f =
51 srv_->setCallback (f);
58 = advertise<jsk_recognition_msgs::BoundingBoxArray>(*
pnh_,
"output_box", 1);
61 = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output_indices", 1);
72 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
89 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
90 std::vector<size_t>& keep)
92 for (
size_t i = 0; i < box_array_msg->boxes.size(); i++) {
93 jsk_recognition_msgs::BoundingBox
box = box_array_msg->boxes[i];
142 jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
143 filtered_box_array.header = box_array_msg->header;
145 std::vector<size_t> keep;
147 for (
size_t j = 0; j < keep.size(); j++)
150 filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
157 size_t pass_count = keep.size();
158 size_t remove_count = box_array_msg->boxes.size() - pass_count;
164 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
165 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg)
169 if (box_array_msg->boxes.size() != indices_msg->cluster_indices.size()) {
171 "the size of message ~input_box and ~input_indices are different");
176 jsk_recognition_msgs::BoundingBoxArray filtered_box_array;
177 jsk_recognition_msgs::ClusterPointIndices filtered_indices;
178 filtered_box_array.header = box_array_msg->header;
179 filtered_indices.header = indices_msg->header;
181 std::vector<size_t> keep;
183 for (
size_t j = 0; j < keep.size(); j++)
186 filtered_box_array.boxes.push_back(box_array_msg->boxes[i]);
187 filtered_indices.cluster_indices.push_back(indices_msg->cluster_indices[i]);
195 size_t pass_count = keep.size();
196 size_t remove_count = box_array_msg->boxes.size() - pass_count;
220 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
221 "BoundingBoxArray running");
236 DiagnosticNodelet::updateDiagnostic(stat);
virtual void filterWithIndices(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
bool filter_limit_negative_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_box_
void filterBoundingBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, std::vector< size_t > &keep)
virtual void configCallback(Config &config, uint32_t level)
jsk_pcl_ros::BoundingBoxFilterConfig Config
virtual void unsubscribe()
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::BoundingBoxFilter, nodelet::Nodelet)
virtual void add(double v)
virtual void filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg)
jsk_recognition_utils::Counter remove_counter_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
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)
jsk_recognition_utils::Counter pass_counter_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Publisher filtered_box_pub_
void add(const std::string &key, const T &val)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
ros::Publisher filtered_indices_pub_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Connection registerCallback(const C &callback)