37 #include <pcl/sample_consensus/method_types.h> 38 #include <pcl/sample_consensus/model_types.h> 39 #include <pcl/segmentation/sac_segmentation.h> 40 #include <pcl/filters/extract_indices.h> 48 ConnectionBasedNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
52 srv_->setCallback (f);
59 NODELET_ERROR(
"Cannot use ~use_imu_perpendicular and ~use_imu_parallel at the same time");
68 pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output_indices", 1);
70 = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*
pnh_,
"output_coefficients", 1);
71 pub_polygons_ = advertise<jsk_recognition_msgs::PolygonArray>(*
pnh_,
"output_polygons", 1);
93 sync_imu_ = boost::make_shared<message_filters::Synchronizer<SyncImuPolicy> >(100);
103 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
113 = boost::make_shared<message_filters::Synchronizer<SyncClusterPolicy> >(100);
155 const pcl::PointCloud<PointT>::Ptr& input,
156 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
157 const Eigen::Vector3f& imu_vector,
158 std::vector<pcl::PointIndices::Ptr>& output_inliers,
159 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
160 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons)
162 pcl::PointCloud<PointT>::Ptr rest_cloud (
new pcl::PointCloud<PointT>);
163 pcl::PointCloud<pcl::Normal>::Ptr rest_normal (
new pcl::PointCloud<pcl::Normal>);
164 *rest_cloud = *input;
165 *rest_normal = *normal;
170 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
171 pcl::ModelCoefficients::Ptr
coefficients (
new pcl::ModelCoefficients);
173 pcl::SACSegmentation<PointT> seg;
174 seg.setOptimizeCoefficients (
true);
176 seg.setMethodType (pcl::SAC_RANSAC);
178 seg.setInputCloud(rest_cloud);
181 seg.setModelType(pcl::SACMODEL_PARALLEL_PLANE);
182 seg.setAxis(imu_vector);
186 seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
187 seg.setAxis(imu_vector);
191 seg.setModelType (pcl::SACMODEL_PLANE);
193 seg.segment (*inliers, *coefficients);
196 pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
197 seg.setOptimizeCoefficients (
true);
199 seg.setMethodType (pcl::SAC_RANSAC);
202 seg.setInputCloud(rest_cloud);
203 seg.setInputNormals(rest_normal);
206 seg.setModelType (pcl::SACMODEL_NORMAL_PARALLEL_PLANE);
207 seg.setAxis(imu_vector);
211 seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
212 seg.setAxis(imu_vector);
216 seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
218 seg.segment (*inliers, *coefficients);
222 output_inliers.push_back(inliers);
223 output_coefficients.push_back(coefficients);
225 input, inliers, coefficients);
226 output_polygons.push_back(convex);
235 pcl::PointCloud<PointT>::Ptr next_rest_cloud
236 (
new pcl::PointCloud<PointT>);
237 pcl::PointCloud<pcl::Normal>::Ptr next_rest_normal
238 (
new pcl::PointCloud<pcl::Normal>);
239 pcl::ExtractIndices<PointT>
ex;
240 ex.setInputCloud(rest_cloud);
241 ex.setIndices(inliers);
242 ex.setNegative(
true);
243 ex.setKeepOrganized(
true);
244 ex.filter(*next_rest_cloud);
246 pcl::ExtractIndices<pcl::Normal> ex_normal;
247 ex_normal.setInputCloud(rest_normal);
248 ex_normal.setIndices(inliers);
249 ex_normal.setNegative(
true);
250 ex_normal.setKeepOrganized(
true);
251 ex_normal.filter(*next_rest_normal);
253 if (next_rest_cloud->points.size() <
min_points_) {
257 rest_cloud = next_rest_cloud;
258 rest_normal = next_rest_normal;
263 const sensor_msgs::PointCloud2::ConstPtr&
msg,
264 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters)
267 pcl::PointCloud<PointT>::Ptr input (
new pcl::PointCloud<PointT>);
269 std::vector<pcl::PointIndices::Ptr> cluster_indices
271 pcl::ExtractIndices<PointT>
ex;
272 ex.setInputCloud(input);
273 ex.setKeepOrganized(
true);
274 std::vector<pcl::PointIndices::Ptr> all_inliers;
275 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients;
276 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> all_convexes;
277 for (
size_t i = 0; i < cluster_indices.size(); i++) {
278 pcl::PointIndices::Ptr indices = cluster_indices[i];
279 pcl::PointCloud<PointT>::Ptr cluster_cloud (
new pcl::PointCloud<PointT>);
280 pcl::PointCloud<pcl::Normal>::Ptr normal (
new pcl::PointCloud<pcl::Normal>);
281 ex.setIndices(indices);
283 ex.filter(*cluster_cloud);
284 std::vector<pcl::PointIndices::Ptr> inliers;
286 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
287 Eigen::Vector3f dummy_imu_vector;
293 publishResult(msg->header, all_inliers, all_coefficients, all_convexes);
297 const std_msgs::Header&
header,
298 const std::vector<pcl::PointIndices::Ptr>& inliers,
299 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
300 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes)
302 jsk_recognition_msgs::ClusterPointIndices ros_indices_output;
303 jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients_output;
304 jsk_recognition_msgs::PolygonArray ros_polygon_output;
305 ros_indices_output.header =
header;
306 ros_coefficients_output.header =
header;
307 ros_polygon_output.header =
header;
308 ros_indices_output.cluster_indices
310 ros_coefficients_output.coefficients
314 for (
size_t i = 0; i < convexes.size(); i++) {
315 geometry_msgs::PolygonStamped
polygon;
317 polygon.polygon = convexes[i]->toROSMsg();
318 ros_polygon_output.polygons.push_back(polygon);
324 const sensor_msgs::PointCloud2::ConstPtr&
msg,
325 const sensor_msgs::Imu::ConstPtr& imu_msg)
327 segmentWithImu(msg, sensor_msgs::PointCloud2::ConstPtr(), imu_msg);
331 const sensor_msgs::PointCloud2::ConstPtr&
msg,
332 const sensor_msgs::PointCloud2::ConstPtr& normal_msg,
333 const sensor_msgs::Imu::ConstPtr& imu_msg)
336 pcl::PointCloud<PointT>::Ptr input (
new pcl::PointCloud<PointT>);
337 pcl::PointCloud<pcl::Normal>::Ptr
338 normal (
new pcl::PointCloud<pcl::Normal>);
343 geometry_msgs::Vector3Stamped stamped_imu, transformed_stamped_imu;
344 stamped_imu.header = imu_msg->header;
345 stamped_imu.vector = imu_msg->linear_acceleration;
348 msg->header.frame_id, imu_msg->header.frame_id, imu_msg->header.stamp,
351 msg->header.frame_id, stamped_imu, transformed_stamped_imu);
352 Eigen::Vector3d imu_vectord;
353 Eigen::Vector3f imu_vector;
355 jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector3d, Eigen::Vector3f>(
356 imu_vectord, imu_vector);
357 imu_vector = - imu_vector;
359 std::vector<pcl::PointIndices::Ptr> inliers;
361 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
363 inliers, coefficients, convexes);
367 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
370 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
373 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
379 const sensor_msgs::PointCloud2::ConstPtr&
msg,
380 const sensor_msgs::PointCloud2::ConstPtr& msg_normal)
383 pcl::PointCloud<PointT>::Ptr input (
new pcl::PointCloud<PointT>);
384 pcl::PointCloud<pcl::Normal>::Ptr normal (
new pcl::PointCloud<pcl::Normal>);
389 std::vector<pcl::PointIndices::Ptr> inliers;
391 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
392 Eigen::Vector3f dummy_imu_vector;
394 inliers, coefficients, convexes);
399 const sensor_msgs::PointCloud2::ConstPtr&
msg)
401 segment(msg, sensor_msgs::PointCloud2::ConstPtr());
ros::Publisher pub_coefficients_
virtual void segmentWithImu(const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
#define NODELET_ERROR(...)
virtual void publishResult(const std_msgs::Header &header, const std::vector< pcl::PointIndices::Ptr > &inliers, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_polygons_
double max(const OneDataStat &d)
wrapper function for max method for boost::function
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
virtual void segmentWithClusters(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< SyncClusterPolicy > > sync_cluster_
virtual void configCallback(Config &config, uint32_t level)
bool use_imu_perpendicular_
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
boost::shared_ptr< message_filters::Synchronizer< SyncNormalImuPolicy > > sync_normal_imu_
virtual void unsubscribe()
void appendVector(std::vector< T > &a, const std::vector< T > &b)
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
jsk_pcl_ros::MultiPlaneSACSegmentationConfig Config
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_clusters_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MultiPlaneSACSegmentation, nodelet::Nodelet)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
double outlier_threshold_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
#define NODELET_INFO(...)
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)
double normal_distance_weight_
tf::TransformListener * tf_listener_
static tf::TransformListener * getInstance()
ros::Publisher pub_inliers_
virtual void applyRecursiveRANSAC(const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &imu_vector, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_polygons)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncImuPolicy > > sync_imu_