36 #define BOOST_PARAMETER_MAX_ARITY 7 
   41 #include <pcl/people/ground_based_people_detection_app.h> 
   45     DiagnosticNodelet::onInit();
 
   62     Eigen::Matrix3f rgb_intrinsics_matrix;
 
   63     rgb_intrinsics_matrix << 525, 0.0, 319.5, 0.0, 525, 239.5, 0.0, 0.0,
 
   67       rgb_intrinsics_matrix);  
 
   80     srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
 
   81     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   89       advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, 
"boxes", 1);
 
  120     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
 
  122     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr input_cloud(
 
  123       new pcl::PointCloud<pcl::PointXYZRGBA>);
 
  126     std::vector<pcl::people::PersonCluster<pcl::PointXYZRGBA> >
 
  132     jsk_recognition_msgs::BoundingBoxArray bounding_box_array;
 
  133     bounding_box_array.header = cloud_msg->header;
 
  134     jsk_recognition_msgs::BoundingBox bounding_box;
 
  135     bounding_box.header = cloud_msg->header;
 
  137     for (std::vector<pcl::people::PersonCluster<pcl::PointXYZRGBA> >::iterator it =
 
  139          it != clusters.end(); ++it) {
 
  142         bounding_box.pose.position.x = it->getCenter()[0];
 
  143         bounding_box.pose.position.y = it->getCenter()[1] + it->getHeight() / 2;
 
  144         bounding_box.pose.position.z = it->getCenter()[2];
 
  146         bounding_box.pose.orientation.x = 0.0;
 
  147         bounding_box.pose.orientation.y = 0.0;
 
  148         bounding_box.pose.orientation.z = 0.0;
 
  149         bounding_box.pose.orientation.w = 1.0;
 
  152         bounding_box.dimensions.y = it->getHeight() + 0.3;
 
  155         bounding_box_array.boxes.push_back(bounding_box);
 
  162     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr&
 
  164     if (coefficients_msg->coefficients.size() >= 1) {
 
  170     const pcl_msgs::ModelCoefficients& coefficients) {
 
  172     for (
int i = 0; 
i < 4; ++
i) {
 
  178     const sensor_msgs::CameraInfo::ConstPtr& info_msg) {
 
  182     Eigen::Matrix3f rgb_intrinsics_matrix;
 
  187       rgb_intrinsics_matrix);