#include <people_detection.h>
|  | 
| typedef jsk_pcl_ros::PeopleDetectionConfig | Config | 
|  | 
Definition at line 84 of file people_detection.h.
 
◆ Config
◆ PeopleDetection()
  
  | 
        
          | jsk_pcl_ros::PeopleDetection::PeopleDetection | ( |  | ) |  |  | inline | 
 
 
◆ configCallback()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protected | 
 
 
◆ detect()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::detect | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg | ) |  |  | protectedvirtual | 
 
 
◆ ground_coeffs_callback()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::ground_coeffs_callback | ( | const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr & | coefficients_msg | ) |  |  | protectedvirtual | 
 
 
◆ infoCallback()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::infoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | info_msg | ) |  |  | protectedvirtual | 
 
 
◆ onInit()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ set_ground_coeffs()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::set_ground_coeffs | ( | const pcl_msgs::ModelCoefficients & | coefficients | ) |  |  | protectedvirtual | 
 
 
◆ subscribe()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void jsk_pcl_ros::PeopleDetection::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ box_depth_
  
  | 
        
          | double jsk_pcl_ros::PeopleDetection::box_depth_ |  | protected | 
 
 
◆ box_width_
  
  | 
        
          | double jsk_pcl_ros::PeopleDetection::box_width_ |  | protected | 
 
 
◆ ground_coeffs_
◆ latest_camera_info_
  
  | 
        
          | sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::PeopleDetection::latest_camera_info_ |  | protected | 
 
 
◆ min_confidence_
  
  | 
        
          | double jsk_pcl_ros::PeopleDetection::min_confidence_ |  | protected | 
 
 
◆ mutex_
◆ people_detector_
  
  | 
        
          | pcl::people::GroundBasedPeopleDetectionApp<pcl::PointXYZRGBA> jsk_pcl_ros::PeopleDetection::people_detector_ |  | protected | 
 
 
◆ people_height_threshold_
  
  | 
        
          | double jsk_pcl_ros::PeopleDetection::people_height_threshold_ |  | protected | 
 
 
◆ person_classifier_
  
  | 
        
          | pcl::people::PersonClassifier<pcl::RGB> jsk_pcl_ros::PeopleDetection::person_classifier_ |  | protected | 
 
 
◆ pub_box_
◆ queue_size_
  
  | 
        
          | int jsk_pcl_ros::PeopleDetection::queue_size_ |  | protected | 
 
 
◆ srv_
◆ sub_cloud_
◆ sub_coefficients_
◆ sub_info_
◆ trained_filename_
  
  | 
        
          | std::string jsk_pcl_ros::PeopleDetection::trained_filename_ |  | protected | 
 
 
◆ voxel_size_
  
  | 
        
          | double jsk_pcl_ros::PeopleDetection::voxel_size_ |  | protected | 
 
 
The documentation for this class was generated from the following files: