Go to the documentation of this file.
37 #ifndef BOUNDING_BOX_FILTER_H_
38 #define BOUNDING_BOX_FILTER_H_
41 #include <dynamic_reconfigure/server.h>
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>
55 class BoundingBoxFilter:
public jsk_topic_tools::DiagnosticNodelet
58 typedef jsk_pcl_ros::BoundingBoxFilterConfig
Config;
61 jsk_recognition_msgs::BoundingBoxArray,
62 jsk_recognition_msgs::ClusterPointIndices
74 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg);
76 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
77 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg);
84 const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array_msg,
85 std::vector<size_t>& keep);
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::BoundingBoxArray, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
jsk_recognition_utils::Counter pass_counter_
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual void filter(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg)
void filterBoundingBoxes(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, std::vector< size_t > &keep)
virtual void filterWithIndices(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg)
bool filter_limit_negative_
jsk_recognition_utils::Counter remove_counter_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Publisher filtered_box_pub_
jsk_pcl_ros::BoundingBoxFilterConfig Config
message_filters::Subscriber< jsk_recognition_msgs::BoundingBoxArray > sub_box_
boost::mutex mutex
global mutex.
ros::Publisher filtered_indices_pub_
virtual ~BoundingBoxFilter()
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:10