#include <extract_cuboid_particles_top_n.h>
| Public Types | |
| typedef ExtractParticlesTopNBaseConfig | Config | 
| typedef boost::shared_ptr < ExtractCuboidParticlesTopN > | Ptr | 
| Public Member Functions | |
| ExtractCuboidParticlesTopN () | |
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | extract (const sensor_msgs::PointCloud2::ConstPtr &msg) | 
| virtual void | onInit () | 
| virtual void | publishBoxArray (const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header) | 
| virtual void | publishPoseArray (const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header) | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| boost::mutex | mutex_ | 
| ros::Publisher | pub_ | 
| ros::Publisher | pub_box_array_ | 
| ros::Publisher | pub_pose_array_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| ros::Subscriber | sub_ | 
| double | top_n_ratio_ | 
Definition at line 60 of file extract_cuboid_particles_top_n.h.
| typedef ExtractParticlesTopNBaseConfig jsk_pcl_ros::ExtractCuboidParticlesTopN::Config | 
Definition at line 64 of file extract_cuboid_particles_top_n.h.
| typedef boost::shared_ptr<ExtractCuboidParticlesTopN> jsk_pcl_ros::ExtractCuboidParticlesTopN::Ptr | 
Definition at line 63 of file extract_cuboid_particles_top_n.h.
Definition at line 65 of file extract_cuboid_particles_top_n.h.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 67 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::extract | ( | const sensor_msgs::PointCloud2::ConstPtr & | msg | ) |  [protected, virtual] | 
Definition at line 73 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 44 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::publishBoxArray | ( | const pcl::PointCloud< pcl::tracking::ParticleCuboid > & | particles, | 
| const std_msgs::Header & | header | ||
| ) |  [protected, virtual] | 
Definition at line 102 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::publishPoseArray | ( | const pcl::PointCloud< pcl::tracking::ParticleCuboid > & | particles, | 
| const std_msgs::Header & | header | ||
| ) |  [protected, virtual] | 
Definition at line 126 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 57 of file extract_cuboid_particles_top_n_nodelet.cpp.
| void jsk_pcl_ros::ExtractCuboidParticlesTopN::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 62 of file extract_cuboid_particles_top_n_nodelet.cpp.
Definition at line 79 of file extract_cuboid_particles_top_n.h.
Definition at line 80 of file extract_cuboid_particles_top_n.h.
Definition at line 81 of file extract_cuboid_particles_top_n.h.
Definition at line 82 of file extract_cuboid_particles_top_n.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::ExtractCuboidParticlesTopN::srv_  [protected] | 
Definition at line 84 of file extract_cuboid_particles_top_n.h.
Definition at line 83 of file extract_cuboid_particles_top_n.h.
| double jsk_pcl_ros::ExtractCuboidParticlesTopN::top_n_ratio_  [protected] | 
Definition at line 85 of file extract_cuboid_particles_top_n.h.