extract_cuboid_particles_top_n_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
40 
41 namespace jsk_pcl_ros
42 {
43  // Do nothing
45  {
46  DiagnosticNodelet::onInit();
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
48  typename dynamic_reconfigure::Server<Config>::CallbackType f =
49  boost::bind (&ExtractCuboidParticlesTopN::configCallback, this, _1, _2);
50  srv_->setCallback (f);
51  pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "output", 1);
52  pub_pose_array_ = advertise<jsk_recognition_msgs::WeightedPoseArray>(*pnh_, "output/pose_array", 1);
53  pub_box_array_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output/box_array", 1);
55  }
56 
58  {
59  sub_ = pnh_->subscribe("input", 1, &ExtractCuboidParticlesTopN::extract, this);
60  }
61 
63  {
64  sub_.shutdown();
65  }
66 
67  void ExtractCuboidParticlesTopN::configCallback(Config& config, uint32_t level)
68  {
69  boost::mutex::scoped_lock lock(mutex_);
70  top_n_ratio_ = config.top_n_ratio;
71  }
72 
73  void ExtractCuboidParticlesTopN::extract(const sensor_msgs::PointCloud2::ConstPtr& msg)
74  {
75  vital_checker_->poke();
76  boost::mutex::scoped_lock lock(mutex_);
77  typename pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr cloud(new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
78  typename pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr cloud_filtered(new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
79  pcl::fromROSMsg(*msg, *cloud);
80  // Sort particles
81  std::sort(cloud->points.begin(), cloud->points.end(),
82  compareParticleWeight<pcl::tracking::ParticleCuboid>);
83  // Take top-n points
84  double sum = 0;
85  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
86  size_t i = 0;
87  while (sum < top_n_ratio_ && i < cloud->points.size()) {
88  //new_particles.push_back(cloud->points[i]);
89  indices->indices.push_back((int)i);
90  sum += cloud->points[i].weight;
91  i++;
92  }
93  pcl::ExtractIndices<pcl::tracking::ParticleCuboid> ex;
94  ex.setInputCloud(cloud);
95  ex.setIndices(indices);
96  ex.filter(*cloud_filtered);
97  publishPointIndices(pub_, *indices, msg->header);
98  publishBoxArray(*cloud_filtered, msg->header);
99  publishPoseArray(*cloud_filtered, msg->header);
100  }
101 
103  const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
104  const std_msgs::Header& header)
105  {
106  if (pub_box_array_.getNumSubscribers() > 0) {
107  jsk_recognition_msgs::BoundingBoxArray box_array;
108  box_array.header = header;
109  box_array.boxes.resize(particles.points.size());
110  for (size_t i = 0; i < particles.points.size(); i++) {
111  pcl::tracking::ParticleCuboid p = particles.points[i];
112  jsk_recognition_msgs::BoundingBox box;
113  box.header = header;
114  Eigen::Affine3f pose = p.toEigenMatrix();
115  tf::poseEigenToMsg(pose, box.pose);
116  box.dimensions.x = p.dx;
117  box.dimensions.y = p.dy;
118  box.dimensions.z = p.dz;
119  box.value = p.weight;
120  box_array.boxes[i] = box;
121  }
122  pub_box_array_.publish(box_array);
123  }
124  }
125 
127  const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
128  const std_msgs::Header& header)
129  {
131  jsk_recognition_msgs::WeightedPoseArray weighted_pose_array;
132  weighted_pose_array.header = header;
133  weighted_pose_array.poses.header = header;
134  for (size_t i = 0; i < particles.points.size(); i++) {
135  pcl::tracking::ParticleCuboid p = particles.points[i];
136  geometry_msgs::Pose ros_pose;
137  Eigen::Affine3f pose = p.toEigenMatrix();
138  tf::poseEigenToMsg(pose, ros_pose);
139  weighted_pose_array.poses.poses.push_back(ros_pose);
140  weighted_pose_array.weights.push_back(p.weight);
141  }
142  pub_pose_array_.publish(weighted_pose_array);
143  }
144  }
145 
146 }
147 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void publish(const boost::shared_ptr< M > &message) const
virtual void publishPoseArray(const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void publishPointIndices(ros::Publisher &pub, const pcl::PointIndices &indices, const std_msgs::Header &header)
Eigen::Affine3f toEigenMatrix() const
pose
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void publishBoxArray(const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header)
virtual void extract(const sensor_msgs::PointCloud2::ConstPtr &msg)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
uint32_t getNumSubscribers() const
T sum(T *pf, int length)
p
cloud
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ExtractCuboidParticlesTopN, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46