35 #define BOOST_PARAMETER_MAX_ARITY 7 37 #include <pcl/registration/sample_consensus_prerejective.h> 38 #include <pcl/segmentation/sac_segmentation.h> 39 #include <pcl/features/fpfh_omp.h> 48 DiagnosticNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (f);
57 reference_sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
64 pub_pose_ = advertise<geometry_msgs::PoseStamped>(*
pnh_,
"output", 1);
65 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output/cloud", 1);
71 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
87 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
88 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
99 Config &config, uint32_t level)
111 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
112 const sensor_msgs::PointCloud2::ConstPtr& feature_msg)
120 pcl::PointCloud<pcl::PointNormal>::Ptr
121 cloud (
new pcl::PointCloud<pcl::PointNormal>);
122 pcl::PointCloud<pcl::PointNormal>::Ptr
123 object_aligned (
new pcl::PointCloud<pcl::PointNormal>);
124 pcl::PointCloud<pcl::FPFHSignature33>::Ptr
125 feature (
new pcl::PointCloud<pcl::FPFHSignature33>);
129 pcl::SampleConsensusPrerejective<pcl::PointNormal,
131 pcl::FPFHSignature33> align;
136 align.setInputTarget(cloud);
137 align.setTargetFeatures(feature);
140 align.setNumberOfSamples(3);
147 align.align (*object_aligned);
149 if (align.hasConverged ())
153 Eigen::Affine3f transformation(align.getFinalTransformation());
154 geometry_msgs::PoseStamped ros_pose;
156 ros_pose.header = cloud_msg->header;
159 pcl::PointCloud<pcl::PointNormal>::Ptr
160 result_cloud (
new pcl::PointCloud<pcl::PointNormal>);
161 pcl::transformPointCloud(
163 sensor_msgs::PointCloud2 ros_cloud;
165 ros_cloud.header = cloud_msg->header;
ros::Publisher pub_cloud_
double similarity_threshold_
#define NODELET_ERROR(...)
double max_correspondence_distance_
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > reference_sync_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_feature_
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_
virtual void unsubscribe()
double transformation_epsilon_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_feature_
FeatureRegistrationConfig Config
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)
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &feature_msg)
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FeatureRegistration, nodelet::Nodelet)
int correspondence_randomness_
pcl::PointCloud< pcl::FPFHSignature33 >::Ptr reference_feature_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_reference_
Nodelet implementation of jsk_pcl/FeatureRegistration.
#define NODELET_DEBUG(...)