#include <bounding_box_filter.h>
Public Types | |
typedef jsk_pcl_ros::BoundingBoxFilterConfig | Config |
typedef message_filters::sync_policies::ExactTime < jsk_recognition_msgs::BoundingBoxArray, jsk_recognition_msgs::ClusterPointIndices > | SyncPolicy |
Protected Member Functions | |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | filter (const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box_array_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | unsubscribe () |
virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Protected Attributes | |
TimeredDiagnosticUpdater::Ptr | diagnostic_updater_ |
bool | filter_limit_negative_ |
ros::Publisher | filtered_box_pub_ |
ros::Publisher | filtered_indices_pub_ |
boost::mutex | mutex_ |
Counter | pass_counter_ |
Counter | remove_counter_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
message_filters::Subscriber < jsk_recognition_msgs::BoundingBoxArray > | sub_box_ |
message_filters::Subscriber < jsk_recognition_msgs::ClusterPointIndices > | sub_indices_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
bool | use_x_dimension_ |
bool | use_y_dimension_ |
bool | use_z_dimension_ |
jsk_topic_tools::VitalChecker::Ptr | vital_checker_ |
double | x_dimension_max_ |
double | x_dimension_min_ |
double | y_dimension_max_ |
double | y_dimension_min_ |
double | z_dimension_max_ |
double | z_dimension_min_ |
Definition at line 55 of file bounding_box_filter.h.
typedef jsk_pcl_ros::BoundingBoxFilterConfig jsk_pcl_ros::BoundingBoxFilter::Config |
Definition at line 58 of file bounding_box_filter.h.
typedef message_filters::sync_policies::ExactTime< jsk_recognition_msgs::BoundingBoxArray, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::BoundingBoxFilter::SyncPolicy |
Definition at line 63 of file bounding_box_filter.h.
void jsk_pcl_ros::BoundingBoxFilter::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 175 of file bounding_box_filter_nodelet.cpp.
void jsk_pcl_ros::BoundingBoxFilter::filter | ( | const jsk_recognition_msgs::BoundingBoxArray::ConstPtr & | box_array_msg, |
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & | indices_msg | ||
) | [protected, virtual] |
Definition at line 97 of file bounding_box_filter_nodelet.cpp.
void jsk_pcl_ros::BoundingBoxFilter::onInit | ( | void | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 40 of file bounding_box_filter_nodelet.cpp.
void jsk_pcl_ros::BoundingBoxFilter::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 82 of file bounding_box_filter_nodelet.cpp.
void jsk_pcl_ros::BoundingBoxFilter::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 91 of file bounding_box_filter_nodelet.cpp.
void jsk_pcl_ros::BoundingBoxFilter::updateDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected, virtual] |
Definition at line 190 of file bounding_box_filter_nodelet.cpp.
Definition at line 92 of file bounding_box_filter.h.
bool jsk_pcl_ros::BoundingBoxFilter::filter_limit_negative_ [protected] |
Definition at line 100 of file bounding_box_filter.h.
Definition at line 85 of file bounding_box_filter.h.
Definition at line 86 of file bounding_box_filter.h.
boost::mutex jsk_pcl_ros::BoundingBoxFilter::mutex_ [protected] |
Definition at line 87 of file bounding_box_filter.h.
Counter jsk_pcl_ros::BoundingBoxFilter::pass_counter_ [protected] |
Definition at line 95 of file bounding_box_filter.h.
Definition at line 94 of file bounding_box_filter.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::BoundingBoxFilter::srv_ [protected] |
Definition at line 81 of file bounding_box_filter.h.
message_filters::Subscriber<jsk_recognition_msgs::BoundingBoxArray> jsk_pcl_ros::BoundingBoxFilter::sub_box_ [protected] |
Definition at line 82 of file bounding_box_filter.h.
message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::BoundingBoxFilter::sub_indices_ [protected] |
Definition at line 83 of file bounding_box_filter.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::BoundingBoxFilter::sync_ [protected] |
Definition at line 84 of file bounding_box_filter.h.
bool jsk_pcl_ros::BoundingBoxFilter::use_x_dimension_ [protected] |
Definition at line 101 of file bounding_box_filter.h.
bool jsk_pcl_ros::BoundingBoxFilter::use_y_dimension_ [protected] |
Definition at line 102 of file bounding_box_filter.h.
bool jsk_pcl_ros::BoundingBoxFilter::use_z_dimension_ [protected] |
Definition at line 103 of file bounding_box_filter.h.
Definition at line 93 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::x_dimension_max_ [protected] |
Definition at line 105 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::x_dimension_min_ [protected] |
Definition at line 104 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::y_dimension_max_ [protected] |
Definition at line 107 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::y_dimension_min_ [protected] |
Definition at line 106 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::z_dimension_max_ [protected] |
Definition at line 109 of file bounding_box_filter.h.
double jsk_pcl_ros::BoundingBoxFilter::z_dimension_min_ [protected] |
Definition at line 108 of file bounding_box_filter.h.