Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_pcl_ros::PeopleDetection Class Reference

#include <people_detection.h>

List of all members.

Public Types

typedef
jsk_pcl_ros::PeopleDetectionConfig 
Config

Public Member Functions

 PeopleDetection ()

Protected Member Functions

void configCallback (Config &config, uint32_t level)
virtual void detect (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void ground_coeffs_callback (const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
virtual void infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual void onInit ()
virtual void set_ground_coeffs (const pcl_msgs::ModelCoefficients &coefficients)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

double box_depth_
double box_width_
Eigen::VectorXf ground_coeffs_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
double min_confidence_
boost::mutex mutex_
pcl::people::GroundBasedPeopleDetectionApp
< pcl::PointXYZRGBA > 
people_detector_
double people_height_threshold_
pcl::people::PersonClassifier
< pcl::RGB > 
person_classifier_
ros::Publisher pub_box_
int queue_size_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
ros::Subscriber sub_cloud_
ros::Subscriber sub_coefficients_
ros::Subscriber sub_info_
std::string trained_filename_
double voxel_size_

Detailed Description

Definition at line 52 of file people_detection.h.


Member Typedef Documentation

typedef jsk_pcl_ros::PeopleDetectionConfig jsk_pcl_ros::PeopleDetection::Config

Definition at line 56 of file people_detection.h.


Constructor & Destructor Documentation

Definition at line 54 of file people_detection.h.


Member Function Documentation

void jsk_pcl_ros::PeopleDetection::configCallback ( Config config,
uint32_t  level 
) [protected]

Definition at line 94 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::detect ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg) [protected, virtual]

Definition at line 119 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::ground_coeffs_callback ( const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &  coefficients_msg) [protected, virtual]

Definition at line 161 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::infoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  info_msg) [protected, virtual]

Definition at line 177 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::onInit ( void  ) [protected, virtual]

Definition at line 44 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::set_ground_coeffs ( const pcl_msgs::ModelCoefficients &  coefficients) [protected, virtual]

Definition at line 169 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::subscribe ( ) [protected, virtual]

Definition at line 105 of file people_detection_nodelet.cpp.

void jsk_pcl_ros::PeopleDetection::unsubscribe ( ) [protected, virtual]

Definition at line 113 of file people_detection_nodelet.cpp.


Member Data Documentation

Definition at line 103 of file people_detection.h.

Definition at line 104 of file people_detection.h.

Eigen::VectorXf jsk_pcl_ros::PeopleDetection::ground_coeffs_ [protected]

Definition at line 101 of file people_detection.h.

sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::PeopleDetection::latest_camera_info_ [protected]

Definition at line 95 of file people_detection.h.

Definition at line 105 of file people_detection.h.

Definition at line 93 of file people_detection.h.

pcl::people::GroundBasedPeopleDetectionApp<pcl::PointXYZRGBA> jsk_pcl_ros::PeopleDetection::people_detector_ [protected]

Definition at line 99 of file people_detection.h.

Definition at line 106 of file people_detection.h.

pcl::people::PersonClassifier<pcl::RGB> jsk_pcl_ros::PeopleDetection::person_classifier_ [protected]

Definition at line 97 of file people_detection.h.

Definition at line 82 of file people_detection.h.

Definition at line 108 of file people_detection.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PeopleDetection::srv_ [protected]

Definition at line 87 of file people_detection.h.

Definition at line 78 of file people_detection.h.

Definition at line 80 of file people_detection.h.

Definition at line 79 of file people_detection.h.

Definition at line 109 of file people_detection.h.

Definition at line 107 of file people_detection.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:47