37 #include <pcl/registration/icp.h>
38 #include <pcl/registration/gicp.h>
39 #include <pcl/registration/ndt.h>
40 #include <pcl/registration/transformation_estimation_lm.h>
41 #include <pcl/registration/warp_point_rigid_3d.h>
44 #include <pcl/common/transforms.h>
48 #include <pcl/registration/correspondence_estimation_organized_projection.h>
49 #include <pcl/registration/correspondence_estimation_normal_shooting.h>
56 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
57 ConnectionBasedNodelet::onInit();
62 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
63 dynamic_reconfigure::Server<Config>::CallbackType
f =
66 srv_->setCallback (
f);
90 *pnh_,
"output/latest_time", 1);
92 *pnh_,
"output/average_time", 1);
136 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
138 sync_->registerCallback(boost::bind(
145 sync_offset_ = boost::make_shared<message_filters::Synchronizer<OffsetSyncPolicy> >(100);
150 sub_ = pnh_->subscribe(
"input", 1,
158 sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
184 const pcl::PointCloud<PointT>& cloud,
185 const std_msgs::Header&
header)
187 if (
pub.getNumSubscribers() > 0) {
188 sensor_msgs::PointCloud2 ros_cloud;
190 ros_cloud.header =
header;
191 pub.publish(ros_cloud);
216 jsk_recognition_msgs::ICPAlignWithBox::Request&
req,
217 jsk_recognition_msgs::ICPAlignWithBox::Response&
res)
226 Eigen::Affine3f offset;
227 pcl::PointCloud<PointT>::Ptr output (
new pcl::PointCloud<PointT>);
228 jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
229 req.target_box,
req.target_cloud,
232 Eigen::Affine3f inversed_offset = offset.inverse();
237 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
242 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
249 jsk_recognition_msgs::ICPAlign::Request&
req,
250 jsk_recognition_msgs::ICPAlign::Response&
res)
253 std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
258 std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
259 pcl::PointCloud<PointT>::Ptr reference_cloud (
new pcl::PointCloud<PointT>);
261 pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (
new pcl::PointCloud<PointT>);
262 for (
size_t i = 0;
i < reference_cloud->points.size();
i++) {
263 PointT p = reference_cloud->points[
i];
264 if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
265 non_nan_reference_cloud->points.push_back(
p);
268 new_references.push_back(non_nan_reference_cloud);
271 non_nan_reference_cloud->points.size(),
272 reference_cloud->points.size());
273 Eigen::Affine3f offset = Eigen::Affine3f::Identity();
274 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
278 req.target_cloud.header);
282 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
288 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
298 const sensor_msgs::PointCloud2::ConstPtr&
msg,
299 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
308 jsk_recognition_msgs::ICPResult
result;
309 result.name = std::string(
"NONE");
318 Eigen::Affine3f offset;
319 pcl::PointCloud<PointT>::Ptr output (
new pcl::PointCloud<PointT>);
320 jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
324 Eigen::Affine3f inversed_offset = offset.inverse();
330 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
334 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
339 const sensor_msgs::PointCloud2::ConstPtr&
msg,
340 const geometry_msgs::PoseStamped::ConstPtr& offset_msg)
349 jsk_recognition_msgs::ICPResult
result;
350 result.name = std::string(
"NONE");
352 result.header = offset_msg->header;
353 result.pose = offset_msg->pose;
360 offset_msg->header.frame_id)) {
361 NODELET_ERROR(
"frame_id does not match. cloud: %s, pose: %s",
362 msg->header.frame_id.c_str(),
363 offset_msg->header.frame_id.c_str());
366 Eigen::Affine3f offset;
367 pcl::PointCloud<PointT>::Ptr
input (
new pcl::PointCloud<PointT>);
369 pcl::PointCloud<PointT>::Ptr output (
new pcl::PointCloud<PointT>);
372 Eigen::Affine3f inversed_offset = offset.inverse();
373 pcl::transformPointCloud(*
input, *output, inversed_offset);
379 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
383 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
400 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
402 Eigen::Affine3f offset = Eigen::Affine3f::Identity();
404 pcl::PointCloud<PointT>::Ptr non_nan_cloud (
new pcl::PointCloud<PointT>);
405 for (
size_t i = 0;
i <
cloud->points.size();
i++) {
407 if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
408 non_nan_cloud->points.push_back(p);
416 const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
425 pcl::PointCloud<PointT>::Ptr reference_cloud (
new pcl::PointCloud<PointT>);
428 pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (
new pcl::PointCloud<PointT>);
429 for (
size_t i = 0;
i < reference_cloud->points.size();
i++) {
430 PointT p = reference_cloud->points[
i];
431 if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
432 non_nan_reference_cloud->points.push_back(p);
441 pcl::PointCloud<PointT>::Ptr& cloud,
442 const Eigen::Affine3f& offset,
443 const std_msgs::Header&
header)
447 double min_score = DBL_MAX;
448 size_t max_index = 0;
449 pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
450 pcl::PointCloud<PointT>::Ptr best_reference;
451 Eigen::Affine3d best_transform_result;
452 Eigen::Affine3f best_offset_result;
453 jsk_recognition_msgs::ICPResult
result;
454 if (
cloud->empty()) {
455 sensor_msgs::PointCloud2 empty_cloud;
456 empty_cloud.header =
header;
459 pcl::PointCloud<PointT> empty_pcl_cloud;
464 geometry_msgs::PoseStamped empty_pose;
465 empty_pose.header =
header;
474 Eigen::Affine3f offset_result;
475 pcl::PointCloud<PointT>::Ptr transformed_cloud(
new pcl::PointCloud<PointT>);
476 Eigen::Affine3d transform_result;
484 if (score < min_score) {
487 best_transform_result = transform_result;
488 best_transformed_cloud = transformed_cloud;
490 best_offset_result = offset_result;
495 if ( min_score == DBL_MAX ) {
496 NODELET_INFO(
"could get valid scorePointcloudAlignment()");
497 geometry_msgs::PoseStamped empty_pose;
498 empty_pose.header =
header;
507 sensor_msgs::PointCloud2 ros_final;
509 ros_final.header =
header;
512 geometry_msgs::PoseStamped ros_result_pose;
513 ros_result_pose.header =
header;
518 pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
519 (
new pcl::PointCloud<PointT>);
520 pcl::transformPointCloud(
521 *best_transformed_cloud, *transformed_cloud_for_debug_result,
522 best_offset_result.inverse());
524 *transformed_cloud_for_debug_result,
header);
525 result.header = ros_result_pose.header;
526 result.pose = ros_result_pose.pose;
528 std::stringstream ss;
535 const sensor_msgs::CameraInfo::ConstPtr&
msg)
542 pcl::PointCloud<PointT>::Ptr& cloud,
543 pcl::PointCloud<PointT>::Ptr& reference,
544 const Eigen::Affine3f& offset,
545 pcl::PointCloud<PointT>::Ptr& output_cloud,
546 Eigen::Affine3d& output_transform)
558 pcl::PointCloud<PointT>::Ptr& cloud,
559 pcl::PointCloud<PointT>::Ptr& reference,
560 const Eigen::Affine3f& offset,
561 pcl::PointCloud<PointT>::Ptr& output_cloud,
562 Eigen::Affine3d& output_transform)
564 pcl::NormalDistributionsTransform<PointT, PointT> ndt;
565 if (reference->points.empty ()) {
569 ndt.setInputSource(reference);
570 if (
cloud->points.empty ()) {
574 ndt.setInputTarget(cloud);
575 pcl::PointCloud<PointT>
final;
577 pcl::transformPointCloud(
final, *output_cloud, offset);
578 Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
579 Eigen::Matrix4d transformation_d;
580 jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
581 transformation, transformation_d);
582 Eigen::Affine3d offsetd;
584 output_transform = offsetd * Eigen::Affine3d(transformation_d);
585 return ndt.getFitnessScore();
589 pcl::PointCloud<PointT>::Ptr& cloud,
590 pcl::PointCloud<PointT>::Ptr& reference,
591 const Eigen::Affine3f& offset,
592 pcl::PointCloud<PointT>::Ptr& output_cloud,
593 Eigen::Affine3d& output_transform)
595 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
596 pcl::GeneralizedIterativeClosestPoint<PointT, PointT> icp;
601 pcl::IterativeClosestPoint<PointT, PointT> icp;
603 pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
604 icp = icp_with_normal;
609 pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
623 if (!model_success_p) {
627 pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
628 corr_projection (
new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
629 corr_projection->setFocalLengths(
model.fx(),
model.fy());
630 corr_projection->setCameraCenters(
model.cx(),
model.cy());
631 icp.setCorrespondenceEstimation(corr_projection);
634 if (reference->points.empty ()) {
638 icp.setInputSource(reference);
639 if (
cloud->points.empty ()) {
643 icp.setInputTarget(cloud);
646 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
647 pcl::registration::WarpPointRigid3D<PointT, PointT>::Ptr warp_func
648 (
new pcl::registration::WarpPointRigid3D<PointT, PointT>);
649 pcl::registration::TransformationEstimationLM<PointT, PointT>::Ptr te
650 (
new pcl::registration::TransformationEstimationLM<PointT, PointT>);
653 (
new pcl::registration::WarpPointRigid3D<PointT, PointT>);
655 (
new pcl::registration::TransformationEstimationLM<PointT, PointT>);
657 te->setWarpFunction(warp_func);
658 icp.setTransformationEstimation(te);
667 pcl::PointCloud<PointT>
final;
669 pcl::transformPointCloud(
final, *output_cloud, offset);
672 Eigen::Matrix4f transformation = icp.getFinalTransformation ();
673 Eigen::Matrix4d transformation_d;
674 jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
675 transformation, transformation_d);
676 Eigen::Affine3d offsetd;
678 output_transform = offsetd * Eigen::Affine3d(transformation_d);
679 return icp.getFitnessScore();
684 pcl::PointCloud<PointT>::Ptr& cloud,
685 pcl::PointCloud<PointT>::Ptr& reference,
686 const Eigen::Affine3f& offset,
687 Eigen::Affine3f& offset_result,
688 pcl::PointCloud<PointT>::Ptr transformed_cloud,
689 Eigen::Affine3d& transform_result)
691 pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
692 (
new pcl::PointCloud<PointT>);
694 transformed_cloud, transform_result);
695 pcl::transformPointCloud(
696 *transformed_cloud, *transformed_cloud_for_debug_result,
698 offset_result = offset;
700 pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
701 (
new pcl::PointCloud<PointT>);
702 Eigen::Affine3d flipped_transform_result;
703 Eigen::Affine3f flipped_offset
704 = offset * Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1));
705 pcl::PointCloud<PointT>::Ptr flipped_cloud (
new pcl::PointCloud<PointT>);
706 pcl::transformPointCloud(
707 *cloud, *flipped_cloud,
708 Eigen::Affine3f(Eigen::AngleAxisf(M_PI, Eigen::Vector3f(0, 0, 1))));
711 flipped_transformed_cloud,
712 flipped_transform_result);
714 if (flipped_score < score) {
715 score = flipped_score;
716 transformed_cloud = flipped_transformed_cloud;
717 transform_result = flipped_transform_result;
718 pcl::transformPointCloud(
719 *transformed_cloud, *transformed_cloud_for_debug_result,
720 flipped_offset.inverse());
721 offset_result = flipped_offset;
728 const sensor_msgs::PointCloud2::ConstPtr&
msg)
736 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
738 pcl::PointCloud<PointT>::Ptr non_nan_cloud (
new pcl::PointCloud<PointT>);
739 for (
size_t i = 0;
i <
cloud->points.size();
i++) {
741 if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
742 non_nan_cloud->points.push_back(p);
749 const jsk_recognition_msgs::PointsArray::ConstPtr&
msg)
757 for (
size_t i = 0;
i <
msg->cloud_list.size();
i++) {
758 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
765 const sensor_msgs::PointCloud2::ConstPtr&
msg)
773 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);