36 #ifndef JSK_PCL_ROS_PEOPLE_DETECTION_H_ 37 #define JSK_PCL_ROS_PEOPLE_DETECTION_H_ 41 #include <jsk_recognition_msgs/BoundingBoxArray.h> 42 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 43 #include <sensor_msgs/CameraInfo.h> 44 #include <sensor_msgs/PointCloud2.h> 46 #include <dynamic_reconfigure/server.h> 47 #include "jsk_pcl_ros/PeopleDetectionConfig.h" 49 #include <pcl/people/ground_based_people_detection_app.h> 56 typedef jsk_pcl_ros::PeopleDetectionConfig
Config;
65 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr&
68 const pcl_msgs::ModelCoefficients& coefficients);
70 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
73 virtual void detect(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
98 pcl::people::GroundBasedPeopleDetectionApp<pcl::PointXYZRGBA>
virtual void ground_coeffs_callback(const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
ros::Subscriber sub_cloud_
void configCallback(Config &config, uint32_t level)
std::string trained_filename_
pcl::people::PersonClassifier< pcl::RGB > person_classifier_
Eigen::VectorXf ground_coeffs_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
virtual void set_ground_coeffs(const pcl_msgs::ModelCoefficients &coefficients)
double people_height_threshold_
ros::Subscriber sub_info_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()
pcl::people::GroundBasedPeopleDetectionApp< pcl::PointXYZRGBA > people_detector_
boost::mutex mutex
global mutex.
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Subscriber sub_coefficients_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
jsk_pcl_ros::PeopleDetectionConfig Config