36 #define BOOST_PARAMETER_MAX_ARITY 7 38 #include <pcl/features/ppf.h> 39 #include <pcl/features/normal_3d.h> 40 #include <pcl/registration/ppf_registration.h> 47 DiagnosticNodelet::onInit();
48 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49 dynamic_reconfigure::Server<Config>::CallbackType
f =
51 srv_->setCallback (f);
56 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output/cloud", 1);
107 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (
new pcl::PointCloud<pcl::Normal> ());
108 pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimation_filter;
109 pcl::search::KdTree<pcl::PointXYZ>::Ptr search_tree (
new pcl::search::KdTree<pcl::PointXYZ> ());
110 pcl::PointCloud<pcl::PointNormal>::Ptr cloud_calculated (
new pcl::PointCloud<pcl::PointNormal> ());
111 normal_estimation_filter.setInputCloud (cloud);
112 normal_estimation_filter.setSearchMethod (search_tree);
113 normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
114 normal_estimation_filter.compute (*cloud_normals);
119 return cloud_calculated;
133 (
const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
134 const sensor_msgs::PointCloud2::ConstPtr& input_reference_cloud)
136 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
144 pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
151 pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (
new pcl::PointCloud<pcl::PPFSignature> ());
157 pcl::PPFHashMapSearch::Ptr hashmap_search (
new pcl::PPFHashMapSearch (12.0
f / 180.0
f *
float (
M_PI), 0.05
f));
158 hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
168 pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
173 Eigen::Affine3f
pose (mat);
175 Eigen::IOFormat CleanFmt(4, 0,
", ",
"\n",
"[",
"]");
179 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (
new pcl::PointCloud<pcl::PointXYZ> ());
180 pcl::transformPointCloud (*reference_cloud, *cloud_output, pose);
183 sensor_msgs::PointCloud2 cloud_msg;
184 toROSMsg(*cloud_output, cloud_msg);
185 geometry_msgs::Pose pose_msg_;
186 geometry_msgs::PoseStamped pose_stamped_msg;
188 pose_stamped_msg.pose = pose_msg_;
191 pose_stamped_msg.header = input_cloud->header;
192 cloud_msg.header = input_cloud->header;
198 (
const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
199 const jsk_recognition_msgs::PointsArray::ConstPtr& input_reference_points_array)
201 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
207 jsk_recognition_msgs::PointsArray::Ptr points_array_msg (
new jsk_recognition_msgs::PointsArray ());
208 geometry_msgs::PoseArray::Ptr pose_array_msg (
new geometry_msgs::PoseArray ());
209 std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > reference_cloud_vector;
210 std::vector<pcl::PointCloud<pcl::PointNormal>::Ptr > reference_cloud_with_normals_vector;
211 std::vector<pcl::PPFHashMapSearch::Ptr > hashmap_search_vector;
214 for (
size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
216 sensor_msgs::PointCloud2 input_reference_cloud = input_reference_points_array->cloud_list[reference_i];
219 pcl::PointCloud<pcl::PointXYZ>::Ptr reference_cloud (
new pcl::PointCloud<pcl::PointXYZ> ());
221 reference_cloud_vector.push_back(reference_cloud);
228 pcl::PointCloud<pcl::PPFSignature>::Ptr reference_cloud_ppf (
new pcl::PointCloud<pcl::PPFSignature> ());
234 pcl::PPFHashMapSearch::Ptr hashmap_search (
new pcl::PPFHashMapSearch (12.0
f / 180.0
f *
float (
M_PI), 0.05
f));
235 hashmap_search->setInputFeatureCloud (reference_cloud_ppf);
236 hashmap_search_vector.push_back(hashmap_search);
240 for (
size_t reference_i=0; reference_i < input_reference_points_array->cloud_list.size(); reference_i++)
247 ppf_registration.setInputSource (reference_cloud_with_normals_vector[reference_i]);
249 pcl::PointCloud<pcl::PointNormal> cloud_output_subsampled;
254 Eigen::Affine3f
pose (mat);
256 Eigen::IOFormat CleanFmt(4, 0,
", ",
"\n",
"[",
"]");
260 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_output (
new pcl::PointCloud<pcl::PointXYZ> ());
261 pcl::transformPointCloud (*reference_cloud_vector[reference_i], *cloud_output, pose);
264 sensor_msgs::PointCloud2 cloud_msg_;
265 toROSMsg(*cloud_output, cloud_msg_);
266 geometry_msgs::Pose pose_msg_;
268 points_array_msg->cloud_list.push_back(cloud_msg_);
269 pose_array_msg->poses.push_back(pose_msg_);
272 pose_array_msg->header = input_cloud->header;
273 points_array_msg->header = input_cloud->header;
ros::Publisher pub_pose_array_
#define NODELET_INFO_STREAM(...)
pcl::PointCloud< pcl::PointNormal >::Ptr reference_cloud_with_normals
double position_clustering_threshold_
virtual void configCallback(Config &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const
virtual void CloudRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const sensor_msgs::PointCloud2::ConstPtr &input_reference_cloud)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< ArraySyncPolicy > > array_sync_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< message_filters::Synchronizer< CloudSyncPolicy > > cloud_sync_
virtual void unsubscribe()
ros::Publisher pub_cloud_
virtual void ArrayRegistration(const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::PointsArray::ConstPtr &input_reference_points_array)
ros::Publisher pub_points_array_
double rotation_clustering_threshold_
jsk_pcl_ros::PPFRegistrationConfig Config
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PPFRegistration, nodelet::Nodelet)
pcl::PPFEstimation< pcl::PointNormal, pcl::PointNormal, pcl::PPFSignature > ppf_estimator
void concatenateFields(PointCloud< PointXYZ > &cloud_xyz, PointCloud< RGB > &cloud_rgb, PointCloud< PointXYZRGB > &cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_reference_cloud_
boost::shared_ptr< message_filters::Synchronizer< CloudApproximateSyncPolicy > > cloud_async_
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)
pcl::PointCloud< pcl::PointNormal >::Ptr cloud_with_normals
boost::shared_ptr< message_filters::Synchronizer< ArrayApproximateSyncPolicy > > array_async_
ros::Publisher pub_pose_stamped_
message_filters::Subscriber< jsk_recognition_msgs::PointsArray > sub_reference_array_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
pcl::PPFRegistration< pcl::PointNormal, pcl::PointNormal > ppf_registration
virtual pcl::PointCloud< pcl::PointNormal >::Ptr calculateNormals(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)