Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/extract_cuboid_particles_top_n.h"
00038 #include "jsk_recognition_utils/pcl_conversion_util.h"
00039 #include "jsk_recognition_utils/pcl_ros_util.h"
00040
00041 namespace jsk_pcl_ros
00042 {
00043
00044 void ExtractCuboidParticlesTopN::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00049 boost::bind (&ExtractCuboidParticlesTopN::configCallback, this, _1, _2);
00050 srv_->setCallback (f);
00051 pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "output", 1);
00052 pub_pose_array_ = advertise<jsk_recognition_msgs::WeightedPoseArray>(*pnh_, "output/pose_array", 1);
00053 pub_box_array_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output/box_array", 1);
00054 onInitPostProcess();
00055 }
00056
00057 void ExtractCuboidParticlesTopN::subscribe()
00058 {
00059 sub_ = pnh_->subscribe("input", 1, &ExtractCuboidParticlesTopN::extract, this);
00060 }
00061
00062 void ExtractCuboidParticlesTopN::unsubscribe()
00063 {
00064 sub_.shutdown();
00065 }
00066
00067 void ExtractCuboidParticlesTopN::configCallback(Config& config, uint32_t level)
00068 {
00069 boost::mutex::scoped_lock lock(mutex_);
00070 top_n_ratio_ = config.top_n_ratio;
00071 }
00072
00073 void ExtractCuboidParticlesTopN::extract(const sensor_msgs::PointCloud2::ConstPtr& msg)
00074 {
00075 vital_checker_->poke();
00076 boost::mutex::scoped_lock lock(mutex_);
00077 typename pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr cloud(new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
00078 typename pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr cloud_filtered(new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
00079 pcl::fromROSMsg(*msg, *cloud);
00080
00081 std::sort(cloud->points.begin(), cloud->points.end(),
00082 compareParticleWeight<pcl::tracking::ParticleCuboid>);
00083
00084 double sum = 0;
00085 pcl::PointIndices::Ptr indices(new pcl::PointIndices);
00086 size_t i = 0;
00087 while (sum < top_n_ratio_ && i < cloud->points.size()) {
00088
00089 indices->indices.push_back((int)i);
00090 sum += cloud->points[i].weight;
00091 i++;
00092 }
00093 pcl::ExtractIndices<pcl::tracking::ParticleCuboid> ex;
00094 ex.setInputCloud(cloud);
00095 ex.setIndices(indices);
00096 ex.filter(*cloud_filtered);
00097 publishPointIndices(pub_, *indices, msg->header);
00098 publishBoxArray(*cloud_filtered, msg->header);
00099 publishPoseArray(*cloud_filtered, msg->header);
00100 }
00101
00102 void ExtractCuboidParticlesTopN::publishBoxArray(
00103 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
00104 const std_msgs::Header& header)
00105 {
00106 if (pub_box_array_.getNumSubscribers() > 0) {
00107 jsk_recognition_msgs::BoundingBoxArray box_array;
00108 box_array.header = header;
00109 box_array.boxes.resize(particles.points.size());
00110 for (size_t i = 0; i < particles.points.size(); i++) {
00111 pcl::tracking::ParticleCuboid p = particles.points[i];
00112 jsk_recognition_msgs::BoundingBox box;
00113 box.header = header;
00114 Eigen::Affine3f pose = p.toEigenMatrix();
00115 tf::poseEigenToMsg(pose, box.pose);
00116 box.dimensions.x = p.dx;
00117 box.dimensions.y = p.dy;
00118 box.dimensions.z = p.dz;
00119 box.value = p.weight;
00120 box_array.boxes[i] = box;
00121 }
00122 pub_box_array_.publish(box_array);
00123 }
00124 }
00125
00126 void ExtractCuboidParticlesTopN::publishPoseArray(
00127 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
00128 const std_msgs::Header& header)
00129 {
00130 if (pub_box_array_.getNumSubscribers() > 0) {
00131 jsk_recognition_msgs::WeightedPoseArray weighted_pose_array;
00132 weighted_pose_array.header = header;
00133 weighted_pose_array.poses.header = header;
00134 for (size_t i = 0; i < particles.points.size(); i++) {
00135 pcl::tracking::ParticleCuboid p = particles.points[i];
00136 geometry_msgs::Pose ros_pose;
00137 Eigen::Affine3f pose = p.toEigenMatrix();
00138 tf::poseEigenToMsg(pose, ros_pose);
00139 weighted_pose_array.poses.poses.push_back(ros_pose);
00140 weighted_pose_array.weights.push_back(p.weight);
00141 }
00142 pub_pose_array_.publish(weighted_pose_array);
00143 }
00144 }
00145
00146 }
00147
00148 #include <pluginlib/class_list_macros.h>
00149 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ExtractCuboidParticlesTopN, nodelet::Nodelet);