36 #define BOOST_PARAMETER_MAX_ARITY 7 43 #include <pcl/segmentation/extract_polygonal_prism_data.h> 44 #include <pcl/filters/extract_indices.h> 45 #include <pcl/filters/crop_box.h> 47 #include <pcl/common/centroid.h> 53 DiagnosticNodelet::onInit();
55 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
56 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
58 srv_->setCallback (f);
59 pnh_->param(
"sensor_frame",
sensor_frame_, std::string(
"odom"));
60 pub_result_ = pnh_->advertise<jsk_recognition_msgs::BoundingBoxArray>(
"output/result", 1);
61 pub_result_pose_ = pnh_->advertise<geometry_msgs::PoseStamped>(
"output/result_pose", 1);
62 pub_particles_ = pnh_->advertise<sensor_msgs::PointCloud2>(
"output/particles", 1);
64 pub_histogram_global_x_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/global/x", 1);
65 pub_histogram_global_y_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/global/y", 1);
66 pub_histogram_global_z_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/global/z", 1);
70 pub_histogram_dx_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/dx", 1);
71 pub_histogram_dy_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/dy", 1);
72 pub_histogram_dz_ = pnh_->advertise<jsk_recognition_msgs::HistogramWithRange>(
"output/histogram/dz", 1);
77 sync_polygon_ = boost::make_shared<message_filters::Synchronizer<PolygonSyncPolicy> >(100);
100 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& polygons)
103 double min_distance = DBL_MAX;
104 Eigen::Vector3f inp = p.getVector3fMap();
105 for (
size_t i = 0; i < polygons.size(); i++) {
108 polygon->project(inp, p);
109 double d = (p - inp).norm();
110 if (d < min_distance) {
119 ParticleCloud::Ptr particles)
122 NODELET_ERROR(
"no valid polygons, skip update relationship");
128 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes(
latest_polygon_msg_->polygons.size());
131 polygon->decomposeToTriangles();
136 #pragma omp parallel for 139 for (
size_t i = 0; i < particles->points.size(); i++) {
142 particles->points[i].plane_index = (int)nearest_index;
147 const sensor_msgs::PointCloud2::ConstPtr&
msg)
153 ParticleCloud::Ptr particles =
tracker_->getParticles();
154 Eigen::Vector4f center;
155 pcl::compute3DCentroid(*particles, center);
162 const sensor_msgs::PointCloud2::ConstPtr&
msg)
168 polygon->decomposeToTriangles();
182 pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles =
initParticles();
190 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
196 std::set<int> all_indices;
199 pcl::ExtractPolygonalPrismData<pcl::PointXYZ> prism_extract;
200 pcl::PointCloud<pcl::PointXYZ>::Ptr
201 boundaries (
new pcl::PointCloud<pcl::PointXYZ>);
202 polygon->boundariesToPointCloud<pcl::PointXYZ>(*boundaries);
203 boundaries->points.push_back(boundaries->points[0]);
204 prism_extract.setInputCloud(cloud);
207 prism_extract.setInputPlanarHull(boundaries);
208 pcl::PointIndices output_indices;
209 prism_extract.segment(output_indices);
210 for (
size_t i = 0; i < output_indices.indices.size(); i++) {
211 all_indices.insert(output_indices.indices[i]);
214 pcl::ExtractIndices<pcl::PointXYZ>
ex;
215 ex.setInputCloud(cloud);
216 pcl::PointIndices::Ptr indices (
new pcl::PointIndices);
217 indices->indices = std::vector<int>(all_indices.begin(), all_indices.end());
218 ex.setIndices(indices);
220 sensor_msgs::PointCloud2 ros_candidate_cloud;
222 ros_candidate_cloud.header = msg->header;
235 ROS_INFO(
"start tracker_->compute()");
237 ROS_INFO(
"done tracker_->compute()");
239 jsk_recognition_msgs::BoundingBoxArray box_array;
240 box_array.header = msg->header;
242 box_array.boxes[0].header = msg->header;
244 geometry_msgs::PoseStamped
pose;
245 pose.pose = box_array.boxes[0].pose;
246 pose.header = box_array.header;
250 ParticleCloud::Ptr particles =
tracker_->getParticles();
262 sensor_msgs::PointCloud2 ros_particles;
264 ros_particles.header = msg->header;
273 const sensor_msgs::PointCloud2::ConstPtr&
msg)
299 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
321 sensor_msgs::PointCloud2 ros_particles;
323 ros_particles.header = msg->header;
328 ParticleCloud::Ptr particles =
tracker_->getParticles();
329 Eigen::Vector4f center;
330 pcl::compute3DCentroid(*particles, center);
340 const double step = 0.001;
342 float max_value = -FLT_MAX;
343 float min_value = FLT_MAX;
344 for (
size_t i = 0; i < particles->points.size(); i++) {
345 max_value =
std::max(max_value, particles->points[i][index]);
346 min_value =
std::min(min_value, particles->points[i][index]);
348 int num = (max_value - min_value) / step + 1;
349 std::vector<unsigned int>
bins(num, 0);
350 for (
size_t i = 0; i < particles->points.size(); i++) {
351 float value = particles->points[i][index];
352 const int bin_index = (value - min_value) / step;
353 const int min_confirmed_bin_index =
std::min(bin_index, num - 1);
354 bins[min_confirmed_bin_index] = bins[min_confirmed_bin_index] + 1;
357 jsk_recognition_msgs::HistogramWithRange histogram;
358 histogram.header =
header;
359 for (
size_t i = 0; i < bins.size(); i++) {
360 jsk_recognition_msgs::HistogramWithRangeBin bin;
361 bin.min_value = i * step + min_value;
362 bin.max_value = (i + 1) * step + min_value;
364 histogram.bins.push_back(bin);
395 return sampled_particle;
407 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
408 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coef_msg)
419 std::vector<double> area_table(polygons.size());
422 area_table[i] = polygons[i]->area();
426 sum += area_table[i];
429 double bin_start = 0.0;
431 if (val >= bin_start && val < bin_start + area_table[i]) {
434 bin_start += area_table[i];
437 NODELET_ERROR(
"should not reach here, failed to select plane randomly");
443 pcl::PointCloud<pcl::tracking::ParticleCuboid>::Ptr particles (
new pcl::PointCloud<pcl::tracking::ParticleCuboid>);
458 p_local.getVector3fMap() = v;
487 particles->points[i] = p_global;
538 std_srvs::EmptyResponse&
res)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
double min(const OneDataStat &d)
wrapper function for min method for boost::function
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &msg)
boost::shared_ptr< message_filters::Synchronizer< PolygonSyncPolicy > > sync_polygon_
ros::Publisher pub_histogram_global_yaw_
virtual size_t getNearestPolygon(const Particle &p, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &polygons)
Compute the nearest polygon to the particle `p'.
double init_world_position_z_min_
#define NODELET_ERROR(...)
double init_local_orientation_pitch_variance_
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
Eigen::Vector3f viewpoint_
std::string sensor_frame_
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
double max(const OneDataStat &d)
wrapper function for max method for boost::function
ros::Publisher pub_histogram_global_x_
virtual void configCallback(Config &config, uint32_t level)
bool use_global_init_yaw_
virtual void updateParticlePolygonRelationship(ParticleCloud::Ptr particles)
Compute distances between particles and polygons and assing each particle to the nearest polygon...
ros::Publisher pub_histogram_global_y_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
double step_roll_variance_
jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr latest_coefficients_msg_
double init_local_orientation_yaw_variance_
double init_local_orientation_roll_mean_
double fast_cloud_threshold_
double step_pitch_variance_
void setParticles(PointCloudStatePtr particles)
static ConvexPolygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
ros::Publisher pub_histogram_global_roll_
double init_global_orientation_yaw_variance_
virtual void publishHistogram(ParticleCloud::Ptr particles, int index, ros::Publisher &pub, const std_msgs::Header &header)
virtual size_t chooseUniformRandomPlaneIndex(const std::vector< Polygon::Ptr > &polygons)
virtual void fastCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointCloud< pcl::PointXYZ >::Ptr candidate_cloud_
static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon &polygon)
ros::ServiceServer srv_reset_
void setCustomSampleFunc(CustomSampleFunc f)
pcl::KdTreeFLANN< pcl::PointXYZ > tree_
boost::mt19937 random_generator_
jsk_recognition_msgs::BoundingBox toBoundingBox()
double init_global_orientation_yaw_mean_
virtual void polygonCallback(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coef_msg)
virtual void likelihood(pcl::PointCloud< pcl::PointXYZ >::ConstPtr input, pcl::tracking::ParticleCuboid &p)
double randomGaussian(double mean, double var, boost::mt19937 &gen)
bool use_init_world_position_z_model_
virtual void unsubscribe()
ros::Publisher pub_histogram_dz_
ros::Publisher pub_candidate_cloud_
virtual pcl::PointCloud< pcl::tracking::ParticleCuboid >::Ptr initParticles()
double step_yaw_variance_
pcl::tracking::ROSCollaborativeParticleFilterTracker< pcl::PointXYZ, pcl::tracking::ParticleCuboid >::Ptr tracker_
ros::Publisher pub_histogram_global_pitch_
ros::Publisher pub_histogram_dy_
double init_local_position_z_min_
double init_local_orientation_yaw_mean_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
ros::Publisher pub_histogram_dx_
double init_local_orientation_roll_variance_
virtual pcl::tracking::ParticleCuboid sample(const pcl::tracking::ParticleCuboid &p)
jsk_recognition_msgs::PolygonArray::ConstPtr latest_polygon_msg_
PlaneSupportedCuboidEstimatorConfig Config
bool support_plane_updated_
void vectorTFToEigen(const tf::Vector3 &t, Eigen::Vector3d &e)
ros::Publisher pub_result_
#define NODELET_INFO(...)
ros::Subscriber sub_fast_cloud_
double computeLikelihood(const pcl::tracking::ParticleCuboid &p, pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::KdTreeFLANN< pcl::PointXYZ > &tree, const Eigen::Vector3f &viewpoint, const std::vector< Polygon::Ptr > &polygons, const std::vector< float > &polygon_likelihood, const Config &config)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void setLikelihoodFunc(CustomLikelihoodFunc f)
double init_world_position_z_max_
virtual bool resetCallback(std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
double init_local_orientation_pitch_mean_
std::vector< Polygon::Ptr > polygons_
ros::Publisher pub_histogram_global_z_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
static tf::TransformListener * getInstance()
ros::Publisher pub_result_pose_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PlaneSupportedCuboidEstimator, nodelet::Nodelet)
ros::Subscriber sub_cloud_
ros::Publisher pub_particles_
tf::TransformListener * tf_
double randomUniform(double min, double max, boost::mt19937 &gen)
double init_local_position_z_max_
bool use_init_polygon_likelihood_