36 #define BOOST_PARAMETER_MAX_ARITY 7 46 DiagnosticNodelet::onInit();
47 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
48 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
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);
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>);
81 std::sort(cloud->points.begin(), cloud->points.end(),
82 compareParticleWeight<pcl::tracking::ParticleCuboid>);
85 pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
89 indices->indices.push_back((
int)i);
90 sum += cloud->points[i].weight;
93 pcl::ExtractIndices<pcl::tracking::ParticleCuboid>
ex;
94 ex.setInputCloud(cloud);
95 ex.setIndices(indices);
96 ex.filter(*cloud_filtered);
103 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
104 const std_msgs::Header&
header)
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++) {
112 jsk_recognition_msgs::BoundingBox
box;
116 box.dimensions.x = p.
dx;
117 box.dimensions.y = p.
dy;
118 box.dimensions.z = p.
dz;
120 box_array.boxes[i] =
box;
127 const pcl::PointCloud<pcl::tracking::ParticleCuboid>& particles,
128 const std_msgs::Header&
header)
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++) {
136 geometry_msgs::Pose ros_pose;
139 weighted_pose_array.poses.poses.push_back(ros_pose);
140 weighted_pose_array.weights.push_back(p.
weight);
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_pose_array_
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)
virtual void unsubscribe()
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
virtual void publishBoxArray(const pcl::PointCloud< pcl::tracking::ParticleCuboid > &particles, const std_msgs::Header &header)
virtual void extract(const sensor_msgs::PointCloud2::ConstPtr &msg)
uint32_t getNumSubscribers() const
ros::Publisher pub_box_array_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ExtractCuboidParticlesTopN, nodelet::Nodelet)
ExtractParticlesTopNBaseConfig Config
virtual void configCallback(Config &config, uint32_t level)