Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_PCL_ROS_EXTRACT_CUBOID_PARTICLES_TOP_N_BASE_H_
00038 #define JSK_PCL_ROS_EXTRACT_CUBOID_PARTICLES_TOP_N_BASE_H_
00039
00040 #include <jsk_topic_tools/diagnostic_nodelet.h>
00041 #include "jsk_pcl_ros/plane_supported_cuboid_estimator.h"
00042 #include <dynamic_reconfigure/server.h>
00043 #include <jsk_pcl_ros/ExtractParticlesTopNBaseConfig.h>
00044 #include <pcl/pcl_base.h>
00045 #include <pcl/impl/pcl_base.hpp>
00046 #include <pcl/filters/extract_indices.h>
00047 #include <pcl/filters/impl/extract_indices.hpp>
00048 #include <jsk_recognition_msgs/WeightedPoseArray.h>
00049 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00050
00051 namespace jsk_pcl_ros
00052 {
00053 template <class PARTICLE_T>
00054 bool compareParticleWeight(const PARTICLE_T& a, const PARTICLE_T& b)
00055 {
00056 return a.weight > b.weight;
00057 }
00058
00059
00060 class ExtractCuboidParticlesTopN: public jsk_topic_tools::DiagnosticNodelet
00061 {
00062 public:
00063 typedef boost::shared_ptr<ExtractCuboidParticlesTopN> Ptr;
00064 typedef ExtractParticlesTopNBaseConfig Config;
00065 ExtractCuboidParticlesTopN(): DiagnosticNodelet("ExtractCuboidParticlesTopN") {}
00066 protected:
00067 virtual void onInit();
00068 virtual void subscribe();
00069 virtual void unsubscribe();
00070 virtual void extract(const sensor_msgs::PointCloud2::ConstPtr& msg);
00071 virtual void publishBoxArray(
00072 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
00073 const std_msgs::Header& header);
00074 virtual void publishPoseArray(
00075 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
00076 const std_msgs::Header& header);
00077 virtual void configCallback(Config& config, uint32_t level);
00078
00079 boost::mutex mutex_;
00080 ros::Publisher pub_;
00081 ros::Publisher pub_box_array_;
00082 ros::Publisher pub_pose_array_;
00083 ros::Subscriber sub_;
00084 boost::shared_ptr<dynamic_reconfigure::Server<Config> > srv_;
00085 double top_n_ratio_;
00086
00087 private:
00088
00089 };
00090
00091 }
00092
00093 #endif