38 #include <pcl/segmentation/sac_segmentation.h> 39 #include <pcl/filters/extract_indices.h> 40 #include <pcl/io/io.h> 48 ConnectionBasedNodelet::onInit();
53 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
56 *
pnh_,
"output_coefficients", 1);
57 pub_edges_ = advertise<jsk_recognition_msgs::SegmentArray>(
58 *
pnh_,
"output_edges", 1);
60 *
pnh_,
"output_outlier_removed", 1);
62 *
pnh_,
"output_outlier_removed_coefficients", 1);
64 *
pnh_,
"output_outlier_removed_edges", 1);
68 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
69 dynamic_reconfigure::Server<Config>::CallbackType
f =
71 srv_->setCallback (f);
83 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
105 const pcl::ModelCoefficients::Ptr coefficients)
107 Eigen::Vector3f
p(coefficients->values[0],
108 coefficients->values[1],
109 coefficients->values[2]);
110 Eigen::Vector3f
d(coefficients->values[3],
111 coefficients->values[4],
112 coefficients->values[5]);
118 const int width,
const int height,
119 const std::vector<int>& indices)
122 int min_y_index, max_y_index, min_x_index, max_x_index;
127 for (
size_t i = 0; i < indices.size(); i++) {
128 int index = indices[i];
129 int x = index % width;
130 int y = index / width;
150 if (min_x_index != max_x_index) {
151 return boost::make_tuple(
152 min_x_index, max_x_index);
155 return boost::make_tuple(
156 min_y_index, max_y_index);
162 const pcl::PointCloud<PointT>::Ptr& cloud,
163 const std::vector<int>& indices,
166 boost::tuple<int, int> min_max
168 PointT min_point = cloud->points[min_max.get<0>()];
169 PointT max_point = cloud->points[min_max.get<1>()];
170 Eigen::Vector3f min_point_f = min_point.getVector3fMap();
171 Eigen::Vector3f max_point_f = max_point.getVector3fMap();
172 Eigen::Vector3f min_foot, max_foot;
173 line->foot(min_point_f, min_foot);
174 line->foot(max_point_f, max_foot);
180 const pcl::PointCloud<PointT>::Ptr& cloud,
181 const std::set<int>& duplicated_set,
182 const std::vector<pcl::PointIndices::Ptr> all_inliers,
183 pcl::PointIndices::Ptr& output_indices)
185 std::vector<int> integrated_indices;
186 for (std::set<int>::iterator it = duplicated_set.begin();
187 it != duplicated_set.end();
192 output_indices->indices = integrated_indices;
196 const pcl::PointCloud<PointT>::Ptr& cloud,
197 const std::vector<pcl::PointIndices::Ptr> all_inliers,
198 const std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
199 std::vector<pcl::PointIndices::Ptr>& output_inliers,
200 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
202 if (all_inliers.size() == 0) {
208 std::vector<jsk_recognition_utils::Line::Ptr>
lines;
209 std::vector<jsk_recognition_utils::Segment::Ptr> segments;
211 for (
size_t i = 0; i < all_inliers.size(); i++) {
212 pcl::PointIndices::Ptr the_inliers = all_inliers[i];
213 pcl::ModelCoefficients::Ptr the_coefficients = all_coefficients[i];
217 lines.push_back(the_line);
218 segments.push_back(the_segment);
225 std::map<int, std::vector<int> > duplication_map;
226 for (
size_t i = 0; i < all_inliers.size() - 1; i++) {
227 duplication_map[i] = std::vector<int>();
230 for (
size_t j = i + 1; j < all_inliers.size(); j++) {
233 Eigen::Vector3f candidate_midpoint;
234 candidate_segment->midpoint(candidate_midpoint);
236 double angle_diff = the_line->angle(*candidate_line);
238 double distance_diff = the_segment->distance(candidate_midpoint);
240 duplication_map[i].push_back(j);
249 std::vector<std::set<int> > duplication_set_list;
250 std::set<int> duplicated_indices;
251 for (
size_t i = 0; i < all_inliers.size(); i++) {
252 std::vector<int> duplication_list;
253 if (i < all_inliers.size() - 1) {
254 duplication_list = duplication_map[i];
256 if (duplicated_indices.find(i) == duplicated_indices.end()) {
257 if (i == all_inliers.size() - 1 || duplication_list.size() == 0) {
258 std::set<int> no_duplication_set;
259 no_duplication_set.insert(i);
260 duplication_set_list.push_back(no_duplication_set);
261 jsk_recognition_utils::addSet<int>(duplicated_indices, no_duplication_set);
264 std::set<int> new_duplication_set;
268 new_duplication_set);
269 duplication_set_list.push_back(new_duplication_set);
271 jsk_recognition_utils::addSet<int>(duplicated_indices, new_duplication_set);
277 for (
size_t i = 0; i < duplication_set_list.size(); i++) {
278 pcl::PointIndices::Ptr integrated_indices (
new pcl::PointIndices);
282 output_inliers.push_back(integrated_indices);
285 pcl::ModelCoefficients::Ptr integrated_coefficients
286 = all_coefficients[(*duplication_set_list[i].begin())];
287 output_coefficients.push_back(integrated_coefficients);
316 const pcl::PointCloud<PointT>::Ptr& cloud,
317 const std::vector<PCLIndicesMsg>& indices,
318 std::vector<pcl::PointIndices::Ptr>& output_inliers,
319 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients)
323 for (
size_t i = 0; i < indices.size(); i++) {
324 std::vector<int> cluster_indices = indices[i].indices;
325 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
326 pcl::ModelCoefficients::Ptr
coefficients (
new pcl::ModelCoefficients);
329 output_inliers.push_back(inliers);
330 output_coefficients.push_back(coefficients);
336 const pcl::PointCloud<PointT>::Ptr& cloud,
337 const std::vector<int>& indices,
338 pcl::PointIndices& inliers,
339 pcl::ModelCoefficients& coefficients)
343 pcl::SACSegmentation<PointT> seg;
344 seg.setOptimizeCoefficients (
true);
345 seg.setModelType (pcl::SACMODEL_LINE);
346 seg.setMethodType (pcl::SAC_RANSAC);
348 seg.setInputCloud(cloud);
349 pcl::PointIndices::Ptr indices_ptr (
new pcl::PointIndices);
350 indices_ptr->indices = indices;
351 seg.setIndices(indices_ptr);
352 seg.segment (inliers, coefficients);
359 const std::vector<pcl::PointIndices::Ptr> inliers,
360 const std::vector<pcl::ModelCoefficients::Ptr> coefficients,
361 const std_msgs::Header&
header)
363 jsk_recognition_msgs::ClusterPointIndices output_ros_msg;
364 jsk_recognition_msgs::ModelCoefficientsArray output_ros_coefficients_msg;
365 jsk_recognition_msgs::SegmentArray output_ros_edges_msg;
366 output_ros_msg.header =
header;
367 output_ros_coefficients_msg.header =
header;
368 output_ros_edges_msg.header =
header;
369 for (
size_t i = 0; i < inliers.size(); i++) {
372 jsk_recognition_msgs::Segment output_edge_msg;
373 output_indices_msg.header =
header;
374 output_indices_msg.indices = inliers[i]->indices;
375 output_ros_msg.cluster_indices.push_back(output_indices_msg);
377 output_coefficients_msg.header =
header;
378 output_coefficients_msg.values = coefficients[i]->values;
379 output_ros_coefficients_msg.coefficients.push_back(output_coefficients_msg);
381 output_edge_msg.start_point.x = coefficients[i]->values[0] - coefficients[i]->values[3];
382 output_edge_msg.start_point.y = coefficients[i]->values[1] - coefficients[i]->values[4];
383 output_edge_msg.start_point.z = coefficients[i]->values[2] - coefficients[i]->values[5];
384 output_edge_msg.end_point.x = coefficients[i]->values[0] + coefficients[i]->values[3];
385 output_edge_msg.end_point.y = coefficients[i]->values[1] + coefficients[i]->values[4];
386 output_edge_msg.end_point.z = coefficients[i]->values[2] + coefficients[i]->values[5];
387 output_ros_edges_msg.segments.push_back(output_edge_msg);
390 pub_coefficients.
publish(output_ros_coefficients_msg);
391 pub_edges.
publish(output_ros_edges_msg);
404 const sensor_msgs::PointCloud2ConstPtr &input,
405 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
408 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
411 std::vector<pcl::PointIndices::Ptr> inliers;
414 removeOutliers(cloud, indices->cluster_indices, inliers, coefficients);
415 std::vector<pcl::PointIndices::Ptr> non_duplicated_inliers;
416 std::vector<pcl::ModelCoefficients::Ptr> non_duplicated_coefficients;
418 non_duplicated_inliers,
419 non_duplicated_coefficients);
423 inliers, coefficients,
428 non_duplicated_inliers,
429 non_duplicated_coefficients,
virtual void removeDuplicatedEdges(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
double duplication_distance_threshold_
#define NODELET_ERROR(...)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
ros::Publisher pub_outlier_removed_coefficients_
virtual jsk_recognition_utils::Line::Ptr lineFromCoefficients(const pcl::ModelCoefficients::Ptr coefficients)
void publish(const boost::shared_ptr< M > &message) const
virtual boost::tuple< int, int > findMinMaxIndex(const int width, const int height, const std::vector< int > &indices)
virtual void removeOutliers(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< PCLIndicesMsg > &indices, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_coefficients_
virtual void publishIndices(ros::Publisher &pub, ros::Publisher &pub_coefficients, ros::Publisher &pub_edges, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, const std_msgs::Header &header)
double duplication_angle_threshold_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::EdgeDepthRefinement, nodelet::Nodelet)
ros::Publisher pub_edges_
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
virtual void removeOutliersByLine(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficients)
jsk_pcl_ros::EdgeDepthRefinementConfig Config
ros::Publisher pub_outlier_removed_edges_
double outlier_distance_threshold_
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 buildGroupFromGraphMap(IntegerGraphMap graph_map, const int from_index, std::vector< int > &to_indices, std::set< int > &output_set)
virtual void refine(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
virtual void integrateDuplicatedIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::set< int > &duplicated_set, const std::vector< pcl::PointIndices::Ptr > all_inliers, pcl::PointIndices::Ptr &output_indices)
pcl::PointIndices PCLIndicesMsg
pcl::ModelCoefficients PCLModelCoefficientMsg
virtual void unsubscribe()
ros::Publisher pub_outlier_removed_indices_
virtual jsk_recognition_utils::Segment::Ptr segmentFromIndices(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const jsk_recognition_utils::Line::Ptr &line)
ros::Publisher pub_indices_