Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/feature_registration.h"
00037 #include <pcl/registration/sample_consensus_prerejective.h>
00038 #include <pcl/segmentation/sac_segmentation.h>
00039 #include <pcl/features/fpfh_omp.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041 #include <pcl_conversions/pcl_conversions.h>
00042 #include "jsk_pcl_ros/pcl_conversion_util.h"
00043
00044 namespace jsk_pcl_ros
00045 {
00046 void FeatureRegistration::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049
00050 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00052 boost::bind (&FeatureRegistration::configCallback, this, _1, _2);
00053 srv_->setCallback (f);
00054
00055
00056
00057 reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00058 sub_input_reference_.subscribe(*pnh_, "input/reference/cloud", 1);
00059 sub_input_reference_feature_.subscribe(*pnh_, "input/reference/feature", 1);
00060 reference_sync_->connectInput(
00061 sub_input_reference_, sub_input_reference_feature_);
00062 reference_sync_->registerCallback(boost::bind(&FeatureRegistration::referenceCallback,
00063 this, _1, _2));
00064 pub_pose_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output", 1);
00065 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
00066 }
00067
00068 void FeatureRegistration::subscribe()
00069 {
00070 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00071 sub_input_.subscribe(*pnh_, "input", 1);
00072 sub_input_feature_.subscribe(*pnh_, "input/feature", 1);
00073 sync_->connectInput(
00074 sub_input_, sub_input_feature_);
00075 sync_->registerCallback(boost::bind(&FeatureRegistration::estimate,
00076 this, _1, _2));
00077 }
00078
00079 void FeatureRegistration::unsubscribe()
00080 {
00081 sub_input_.unsubscribe();
00082 sub_input_feature_.unsubscribe();
00083 }
00084
00085 void FeatureRegistration::referenceCallback(
00086 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00087 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
00088 {
00089 boost::mutex::scoped_lock lock(mutex_);
00090 JSK_NODELET_DEBUG("update reference");
00091 reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
00092 reference_feature_.reset(new pcl::PointCloud<pcl::FPFHSignature33>);
00093 pcl::fromROSMsg(*cloud_msg, *reference_cloud_);
00094 pcl::fromROSMsg(*feature_msg, *reference_feature_);
00095 }
00096
00097 void FeatureRegistration::configCallback(
00098 Config &config, uint32_t level)
00099 {
00100 boost::mutex::scoped_lock lock(mutex_);
00101 max_iterations_ = config.max_iterations;
00102 correspondence_randomness_ = config.correspondence_randomness;
00103 similarity_threshold_ = config.similarity_threshold;
00104 max_correspondence_distance_ = config.max_correspondence_distance;
00105 inlier_fraction_ = config.inlier_fraction;
00106 }
00107
00108 void FeatureRegistration::estimate(
00109 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00110 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
00111 {
00112 boost::mutex::scoped_lock lock(mutex_);
00113 if (!reference_cloud_ || !reference_feature_) {
00114 JSK_NODELET_ERROR("Not yet reference data is available");
00115 return;
00116 }
00117
00118 pcl::PointCloud<pcl::PointNormal>::Ptr
00119 cloud (new pcl::PointCloud<pcl::PointNormal>);
00120 pcl::PointCloud<pcl::PointNormal>::Ptr
00121 object_aligned (new pcl::PointCloud<pcl::PointNormal>);
00122 pcl::PointCloud<pcl::FPFHSignature33>::Ptr
00123 feature (new pcl::PointCloud<pcl::FPFHSignature33>);
00124 pcl::fromROSMsg(*cloud_msg, *cloud);
00125 pcl::fromROSMsg(*feature_msg, *feature);
00126
00127 pcl::SampleConsensusPrerejective<pcl::PointNormal,
00128 pcl::PointNormal,
00129 pcl::FPFHSignature33> align;
00130
00131 align.setInputSource(reference_cloud_);
00132 align.setSourceFeatures(reference_feature_);
00133
00134 align.setInputTarget(cloud);
00135 align.setTargetFeatures(feature);
00136
00137 align.setMaximumIterations(max_iterations_);
00138 align.setNumberOfSamples(3);
00139 align.setCorrespondenceRandomness(correspondence_randomness_);
00140 align.setSimilarityThreshold(similarity_threshold_);
00141 align.setMaxCorrespondenceDistance(max_correspondence_distance_);
00142 align.setInlierFraction(inlier_fraction_);
00143 align.align (*object_aligned);
00144
00145 if (align.hasConverged ())
00146 {
00147
00148 printf ("\n");
00149 Eigen::Affine3f transformation(align.getFinalTransformation());
00150 geometry_msgs::PoseStamped ros_pose;
00151 tf::poseEigenToMsg(transformation, ros_pose.pose);
00152 ros_pose.header = cloud_msg->header;
00153 pub_pose_.publish(ros_pose);
00154
00155 pcl::PointCloud<pcl::PointNormal>::Ptr
00156 result_cloud (new pcl::PointCloud<pcl::PointNormal>);
00157 pcl::transformPointCloud(
00158 *reference_cloud_, *result_cloud, transformation);
00159 sensor_msgs::PointCloud2 ros_cloud;
00160 pcl::toROSMsg(*object_aligned, ros_cloud);
00161 ros_cloud.header = cloud_msg->header;
00162 pub_cloud_.publish(ros_cloud);
00163
00164
00165
00166 }
00167 else {
00168 JSK_NODELET_WARN("failed to align pointcloud");
00169 }
00170
00171 }
00172 }
00173
00174 #include <pluginlib/class_list_macros.h>
00175 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::FeatureRegistration, nodelet::Nodelet);