bounding_box_filter.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef BOUNDING_BOX_FILTER_H_
38 #define BOUNDING_BOX_FILTER_H_
39 
40 #include <pcl_ros/pcl_nodelet.h>
41 #include <dynamic_reconfigure/server.h>
44 
47 #include <jsk_recognition_msgs/BoundingBoxArray.h>
48 #include <jsk_recognition_msgs/ClusterPointIndices.h>
49 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
50 #include <jsk_pcl_ros/BoundingBoxFilterConfig.h>
51 #include <jsk_topic_tools/diagnostic_nodelet.h>
52 
53 namespace jsk_pcl_ros
54 {
55  class BoundingBoxFilter: public jsk_topic_tools::DiagnosticNodelet
56  {
57  public:
58  typedef jsk_pcl_ros::BoundingBoxFilterConfig Config;
59 
61  jsk_recognition_msgs::BoundingBoxArray,
62  jsk_recognition_msgs::ClusterPointIndices
63  > SyncPolicy;
64 
65  BoundingBoxFilter() : DiagnosticNodelet("BoundingBoxFilter") {}
66  virtual ~BoundingBoxFilter();
67 
68  protected:
70  // methods
72  virtual void onInit();
73  virtual void filter(
74  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg);
75  virtual void filterWithIndices(
76  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
77  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
78  virtual void configCallback(Config &config, uint32_t level);
79  virtual void updateDiagnostic(
81  virtual void subscribe();
82  virtual void unsubscribe();
84  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
85  std::vector<size_t>& keep);
86 
88  // ROS varariables
97 
99  // Diagnostics Variables
103 
105  // Parameters
108  bool use_x_dimension_;
109  bool use_y_dimension_;
110  bool use_z_dimension_;
111  double x_dimension_min_;
112  double x_dimension_max_;
113  double y_dimension_min_;
114  double y_dimension_max_;
115  double z_dimension_min_;
116  double z_dimension_max_;
117 
118  bool with_indices_;
119 
120  private:
121 
122  };
123 }
124 
125 #endif
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::BoundingBoxFilter::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: bounding_box_filter_nodelet.cpp:259
jsk_pcl_ros::BoundingBoxFilter::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: bounding_box_filter.h:154
jsk_pcl_ros::BoundingBoxFilter::x_dimension_max_
double x_dimension_max_
Definition: bounding_box_filter.h:176
jsk_pcl_ros::BoundingBoxFilter::SyncPolicy
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::BoundingBoxArray, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: bounding_box_filter.h:127
jsk_pcl_ros::BoundingBoxFilter::onInit
virtual void onInit()
Definition: bounding_box_filter_nodelet.cpp:72
geo_util.h
jsk_pcl_ros::BoundingBoxFilter::use_x_dimension_
bool use_x_dimension_
Definition: bounding_box_filter.h:172
time_synchronizer.h
jsk_pcl_ros::BoundingBoxFilter::pass_counter_
jsk_recognition_utils::Counter pass_counter_
Definition: bounding_box_filter.h:166
jsk_pcl_ros::BoundingBoxFilter::unsubscribe
virtual void unsubscribe()
Definition: bounding_box_filter_nodelet.cpp:123
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray >
jsk_pcl_ros::BoundingBoxFilter::z_dimension_min_
double z_dimension_min_
Definition: bounding_box_filter.h:179
jsk_pcl_ros::BoundingBoxFilter::BoundingBoxFilter
BoundingBoxFilter()
Definition: bounding_box_filter.h:129
pcl_nodelet.h
jsk_pcl_ros::BoundingBoxFilter::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: bounding_box_filter_nodelet.cpp:244
jsk_pcl_ros::BoundingBoxFilter::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: bounding_box_filter.h:156
jsk_pcl_ros::BoundingBoxFilter::z_dimension_max_
double z_dimension_max_
Definition: bounding_box_filter.h:180
jsk_pcl_ros::BoundingBoxFilter::filter
virtual void filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg)
Definition: bounding_box_filter_nodelet.cpp:181
jsk_pcl_ros::BoundingBoxFilter::y_dimension_max_
double y_dimension_max_
Definition: bounding_box_filter.h:178
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::BoundingBoxFilter::filterBoundingBoxes
void filterBoundingBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, std::vector< size_t > &keep)
Definition: bounding_box_filter_nodelet.cpp:131
jsk_pcl_ros::BoundingBoxFilter::filterWithIndices
virtual void filterWithIndices(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
Definition: bounding_box_filter_nodelet.cpp:206
jsk_pcl_ros::BoundingBoxFilter::filter_limit_negative_
bool filter_limit_negative_
Definition: bounding_box_filter.h:171
jsk_pcl_ros::BoundingBoxFilter::subscribe
virtual void subscribe()
Definition: bounding_box_filter_nodelet.cpp:110
jsk_pcl_ros::BoundingBoxFilter::remove_counter_
jsk_recognition_utils::Counter remove_counter_
Definition: bounding_box_filter.h:165
jsk_pcl_ros::BoundingBoxFilter::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: bounding_box_filter.h:157
jsk_pcl_ros::BoundingBoxFilter::filtered_box_pub_
ros::Publisher filtered_box_pub_
Definition: bounding_box_filter.h:158
jsk_pcl_ros::BoundingBoxFilter::Config
jsk_pcl_ros::BoundingBoxFilterConfig Config
Definition: bounding_box_filter.h:122
jsk_recognition_utils::Counter
jsk_pcl_ros::BoundingBoxFilter::use_z_dimension_
bool use_z_dimension_
Definition: bounding_box_filter.h:174
jsk_pcl_ros::BoundingBoxFilter::with_indices_
bool with_indices_
Definition: bounding_box_filter.h:182
jsk_pcl_ros::BoundingBoxFilter::sub_box_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_box_
Definition: bounding_box_filter.h:155
pcl_util.h
jsk_pcl_ros::BoundingBoxFilter::x_dimension_min_
double x_dimension_min_
Definition: bounding_box_filter.h:175
jsk_pcl_ros::BoundingBoxFilter::use_y_dimension_
bool use_y_dimension_
Definition: bounding_box_filter.h:173
synchronizer.h
diagnostic_updater::DiagnosticStatusWrapper
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::BoundingBoxFilter::mutex_
boost::mutex mutex_
Definition: bounding_box_filter.h:160
message_filters::sync_policies::ExactTime
jsk_pcl_ros::BoundingBoxFilter::y_dimension_min_
double y_dimension_min_
Definition: bounding_box_filter.h:177
jsk_pcl_ros::BoundingBoxFilter::filtered_indices_pub_
ros::Publisher filtered_indices_pub_
Definition: bounding_box_filter.h:159
jsk_pcl_ros::BoundingBoxFilter::~BoundingBoxFilter
virtual ~BoundingBoxFilter()
Definition: bounding_box_filter_nodelet.cpp:99


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