35 #define BOOST_PARAMETER_MAX_ARITY 7 37 #include <pcl/kdtree/kdtree_flann.h> 38 #include <pcl/sample_consensus/method_types.h> 39 #include <pcl/sample_consensus/model_types.h> 40 #include <pcl/segmentation/sac_segmentation.h> 48 DiagnosticNodelet::onInit();
49 pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 srv_->setCallback (f);
56 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
57 *
pnh_,
"output/indices", 1);
58 pub_polygon_ = advertise<jsk_recognition_msgs::PolygonArray>(
59 *
pnh_,
"output/polygons", 1);
61 *
pnh_,
"output/coefficients", 1);
72 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
88 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
89 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
90 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
91 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg)
96 size_t nr_cluster = polygon_array_msg->polygons.size();
97 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
100 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients
102 coefficients_array_msg->coefficients);
103 std::vector<pcl::PointIndices::Ptr> all_indices
105 std::vector<pcl::PointCloud<PointT>::Ptr> all_clouds
106 = jsk_recognition_utils::convertToPointCloudArray<PointT>(
cloud, all_indices);
107 std::vector<jsk_recognition_utils::Plane::Ptr> planes
111 for (
size_t i = 0; i < nr_cluster; i++) {
112 connection_map[i] = std::vector<int>();
113 connection_map[i].push_back(i);
115 pcl::KdTreeFLANN<PointT> kdtree;
116 pcl::PointCloud<PointT>::Ptr focused_cloud = all_clouds[i];
117 kdtree.setInputCloud(focused_cloud);
120 for (
size_t j = i + 1; j < nr_cluster; j++) {
124 bool is_near_enough =
isNearPointCloud(kdtree, all_clouds[j], target_plane);
125 if (is_near_enough) {
126 connection_map[i].push_back(j);
131 std::vector<std::set<int> > cloud_sets;
134 std::vector<pcl::PointIndices::Ptr> new_indices;
135 std::vector<pcl::ModelCoefficients::Ptr> new_coefficients;
136 for (
size_t i = 0; i < cloud_sets.size(); i++) {
137 pcl::PointIndices::Ptr new_one_indices (
new pcl::PointIndices);
138 new_coefficients.push_back(all_coefficients[*cloud_sets[i].begin()]);
139 for (std::set<int>::iterator it = cloud_sets[i].begin();
140 it != cloud_sets[i].end();
144 if (new_one_indices->indices.size() >
min_size_) {
145 new_indices.push_back(new_one_indices);
150 std::vector<pcl::ModelCoefficients::Ptr> new_refined_coefficients;
151 for (
size_t i = 0; i < new_indices.size(); i++) {
152 pcl::ModelCoefficients::Ptr refined_coefficients
153 =
refinement(cloud, new_indices[i], new_coefficients[i]);
154 new_refined_coefficients.push_back(refined_coefficients);
158 jsk_recognition_msgs::ClusterPointIndices new_ros_indices;
159 jsk_recognition_msgs::ModelCoefficientsArray new_ros_coefficients;
160 jsk_recognition_msgs::PolygonArray new_ros_polygons;
161 new_ros_indices.header = cloud_msg->header;
162 new_ros_coefficients.header = cloud_msg->header;
163 new_ros_polygons.header = cloud_msg->header;
164 for (
size_t i = 0; i < new_indices.size(); i++) {
166 = jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
167 cloud, new_indices[i], new_refined_coefficients[i]);
169 geometry_msgs::PolygonStamped polygon;
170 polygon.polygon = convex->toROSMsg();
171 polygon.header = cloud_msg->header;
172 new_ros_polygons.polygons.push_back(polygon);
173 pcl_msgs::PointIndices ros_indices;
174 ros_indices.header = cloud_msg->header;
175 ros_indices.indices = new_indices[i]->indices;
176 new_ros_indices.cluster_indices.push_back(ros_indices);
177 pcl_msgs::ModelCoefficients ros_coefficients;
178 ros_coefficients.header = cloud_msg->header;
179 ros_coefficients.values = new_refined_coefficients[i]->values;
180 new_ros_coefficients.coefficients.push_back(ros_coefficients);
196 pcl::PointCloud<PointT>::Ptr
cloud,
197 pcl::PointIndices::Ptr indices,
198 pcl::ModelCoefficients::Ptr original_coefficients)
200 pcl::SACSegmentation<PointT> seg;
201 seg.setOptimizeCoefficients (
true);
202 seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
203 seg.setMethodType (pcl::SAC_RANSAC);
206 seg.setInputCloud(cloud);
208 seg.setIndices(indices);
210 Eigen::Vector3f normal (original_coefficients->values[0],
211 original_coefficients->values[1],
212 original_coefficients->values[2]);
218 pcl::PointIndices::Ptr refined_inliers (
new pcl::PointIndices);
219 pcl::ModelCoefficients::Ptr refined_coefficients(
new pcl::ModelCoefficients);
220 seg.segment(*refined_inliers, *refined_coefficients);
221 if (refined_inliers->indices.size() > 0) {
222 return refined_coefficients;
225 return original_coefficients;
230 pcl::KdTreeFLANN<PointT>& kdtree,
231 pcl::PointCloud<PointT>::Ptr
cloud,
234 pcl::PointCloud<PointT>::ConstPtr input_cloud = kdtree.getInputCloud();
235 for (
size_t i = 0; i < cloud->points.size(); i++) {
237 std::vector<int> k_indices;
238 std::vector<float> k_sqr_distances;
240 k_indices, k_sqr_distances, 1) > 0) {
242 const PointT near_p = input_cloud->points[k_indices[0]];
243 Eigen::Affine3f plane_coordinates = target_plane->coordinates();
244 Eigen::Vector3f plane_local_p = plane_coordinates.inverse() * p.getVector3fMap();
245 Eigen::Vector3f plane_local_near_p = plane_coordinates.inverse() * near_p.getVector3fMap();
246 Eigen::Vector3f plane_local_diff = plane_local_near_p - plane_local_p;
247 double perpendicular_distance = std::abs(plane_local_diff[2]);
257 Config &config, uint32_t level)
265 = config.ransac_refinement_outlier_threshold;
std::vector< Plane::Ptr > convertToPlanes(std::vector< pcl::ModelCoefficients::Ptr >)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PlaneConcatenator, nodelet::Nodelet)
double ransac_refinement_eps_angle_
PlaneConcatenatorConfig Config
virtual void unsubscribe()
void publish(const boost::shared_ptr< M > &message) const
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher pub_indices_
std::map< int, std::vector< int > > IntegerGraphMap
double ransac_refinement_outlier_threshold_
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
double connect_angular_threshold_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
double connect_distance_threshold_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
virtual bool isNearPointCloud(pcl::KdTreeFLANN< PointT > &kdtree, pcl::PointCloud< PointT >::Ptr cloud, jsk_recognition_utils::Plane::Ptr target_plane)
double connect_perpendicular_distance_threshold_
int ransac_refinement_max_iteration_
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_coefficients_
virtual pcl::ModelCoefficients::Ptr refinement(pcl::PointCloud< PointT >::Ptr cloud, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr original_coefficients)
void buildAllGroupsSetFromGraphMap(IntegerGraphMap graph_map, std::vector< std::set< int > > &output_sets)
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_array_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_array_msg)
ros::Publisher pub_polygon_
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)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_