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_recognition_utils/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 onInitPostProcess();
00067 }
00068
00069 void FeatureRegistration::subscribe()
00070 {
00071 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00072 sub_input_.subscribe(*pnh_, "input", 1);
00073 sub_input_feature_.subscribe(*pnh_, "input/feature", 1);
00074 sync_->connectInput(
00075 sub_input_, sub_input_feature_);
00076 sync_->registerCallback(boost::bind(&FeatureRegistration::estimate,
00077 this, _1, _2));
00078 }
00079
00080 void FeatureRegistration::unsubscribe()
00081 {
00082 sub_input_.unsubscribe();
00083 sub_input_feature_.unsubscribe();
00084 }
00085
00086 void FeatureRegistration::referenceCallback(
00087 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00088 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
00089 {
00090 boost::mutex::scoped_lock lock(mutex_);
00091 NODELET_DEBUG("update reference");
00092 reference_cloud_.reset(new pcl::PointCloud<pcl::PointNormal>);
00093 reference_feature_.reset(new pcl::PointCloud<pcl::FPFHSignature33>);
00094 pcl::fromROSMsg(*cloud_msg, *reference_cloud_);
00095 pcl::fromROSMsg(*feature_msg, *reference_feature_);
00096 }
00097
00098 void FeatureRegistration::configCallback(
00099 Config &config, uint32_t level)
00100 {
00101 boost::mutex::scoped_lock lock(mutex_);
00102 max_iterations_ = config.max_iterations;
00103 correspondence_randomness_ = config.correspondence_randomness;
00104 similarity_threshold_ = config.similarity_threshold;
00105 max_correspondence_distance_ = config.max_correspondence_distance;
00106 inlier_fraction_ = config.inlier_fraction;
00107 }
00108
00109 void FeatureRegistration::estimate(
00110 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00111 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
00112 {
00113 boost::mutex::scoped_lock lock(mutex_);
00114 if (!reference_cloud_ || !reference_feature_) {
00115 NODELET_ERROR("Not yet reference data is available");
00116 return;
00117 }
00118
00119 pcl::PointCloud<pcl::PointNormal>::Ptr
00120 cloud (new pcl::PointCloud<pcl::PointNormal>);
00121 pcl::PointCloud<pcl::PointNormal>::Ptr
00122 object_aligned (new pcl::PointCloud<pcl::PointNormal>);
00123 pcl::PointCloud<pcl::FPFHSignature33>::Ptr
00124 feature (new pcl::PointCloud<pcl::FPFHSignature33>);
00125 pcl::fromROSMsg(*cloud_msg, *cloud);
00126 pcl::fromROSMsg(*feature_msg, *feature);
00127
00128 pcl::SampleConsensusPrerejective<pcl::PointNormal,
00129 pcl::PointNormal,
00130 pcl::FPFHSignature33> align;
00131
00132 align.setInputSource(reference_cloud_);
00133 align.setSourceFeatures(reference_feature_);
00134
00135 align.setInputTarget(cloud);
00136 align.setTargetFeatures(feature);
00137
00138 align.setMaximumIterations(max_iterations_);
00139 align.setNumberOfSamples(3);
00140 align.setCorrespondenceRandomness(correspondence_randomness_);
00141 align.setSimilarityThreshold(similarity_threshold_);
00142 align.setMaxCorrespondenceDistance(max_correspondence_distance_);
00143 align.setInlierFraction(inlier_fraction_);
00144 align.align (*object_aligned);
00145
00146 if (align.hasConverged ())
00147 {
00148
00149 printf ("\n");
00150 Eigen::Affine3f transformation(align.getFinalTransformation());
00151 geometry_msgs::PoseStamped ros_pose;
00152 tf::poseEigenToMsg(transformation, ros_pose.pose);
00153 ros_pose.header = cloud_msg->header;
00154 pub_pose_.publish(ros_pose);
00155
00156 pcl::PointCloud<pcl::PointNormal>::Ptr
00157 result_cloud (new pcl::PointCloud<pcl::PointNormal>);
00158 pcl::transformPointCloud(
00159 *reference_cloud_, *result_cloud, transformation);
00160 sensor_msgs::PointCloud2 ros_cloud;
00161 pcl::toROSMsg(*object_aligned, ros_cloud);
00162 ros_cloud.header = cloud_msg->header;
00163 pub_cloud_.publish(ros_cloud);
00164
00165
00166
00167 }
00168 else {
00169 NODELET_WARN("failed to align pointcloud");
00170 }
00171
00172 }
00173 }
00174
00175 #include <pluginlib/class_list_macros.h>
00176 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::FeatureRegistration, nodelet::Nodelet);