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);
123 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
125 sync_->registerCallback(boost::bind(
132 sync_offset_ = boost::make_shared<message_filters::Synchronizer<OffsetSyncPolicy> >(100);
145 sync_reference_ = boost::make_shared<message_filters::Synchronizer<ReferenceSyncPolicy> >(100);
171 const pcl::PointCloud<PointT>& cloud,
172 const std_msgs::Header&
header)
175 sensor_msgs::PointCloud2 ros_cloud;
177 ros_cloud.header =
header;
203 jsk_recognition_msgs::ICPAlignWithBox::Request&
req,
204 jsk_recognition_msgs::ICPAlignWithBox::Response&
res)
213 Eigen::Affine3f offset;
214 pcl::PointCloud<PointT>::Ptr
output (
new pcl::PointCloud<PointT>);
215 jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
216 req.target_box, req.target_cloud,
219 Eigen::Affine3f inversed_offset = offset.inverse();
224 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
229 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
236 jsk_recognition_msgs::ICPAlign::Request&
req,
237 jsk_recognition_msgs::ICPAlign::Response&
res)
240 std::vector<pcl::PointCloud<PointT>::Ptr> tmp_reference_cloud_list
245 std::vector<pcl::PointCloud<PointT>::Ptr> new_references;
246 pcl::PointCloud<PointT>::Ptr reference_cloud (
new pcl::PointCloud<PointT>);
248 pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (
new pcl::PointCloud<PointT>);
249 for (
size_t i = 0; i < reference_cloud->points.size(); i++) {
250 PointT p = reference_cloud->points[i];
251 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
252 non_nan_reference_cloud->points.push_back(p);
255 new_references.push_back(non_nan_reference_cloud);
258 non_nan_reference_cloud->points.size(),
259 reference_cloud->points.size());
260 Eigen::Affine3f offset = Eigen::Affine3f::Identity();
261 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
265 req.target_cloud.header);
269 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
275 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
285 const sensor_msgs::PointCloud2::ConstPtr&
msg,
286 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
295 jsk_recognition_msgs::ICPResult
result;
296 result.name = std::string(
"NONE");
297 result.score = DBL_MAX;
298 result.header = box_msg->header;
299 result.pose = box_msg->pose;
305 Eigen::Affine3f offset;
306 pcl::PointCloud<PointT>::Ptr
output (
new pcl::PointCloud<PointT>);
307 jsk_pcl_ros_utils::transformPointcloudInBoundingBox<PointT>(
311 Eigen::Affine3f inversed_offset = offset.inverse();
317 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
321 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
326 const sensor_msgs::PointCloud2::ConstPtr&
msg,
327 const geometry_msgs::PoseStamped::ConstPtr& offset_msg)
336 jsk_recognition_msgs::ICPResult
result;
337 result.name = std::string(
"NONE");
338 result.score = DBL_MAX;
339 result.header = offset_msg->header;
340 result.pose = offset_msg->pose;
347 offset_msg->header.frame_id)) {
348 NODELET_ERROR(
"frame_id does not match. cloud: %s, pose: %s",
349 msg->header.frame_id.c_str(),
350 offset_msg->header.frame_id.c_str());
353 Eigen::Affine3f offset;
354 pcl::PointCloud<PointT>::Ptr input (
new pcl::PointCloud<PointT>);
356 pcl::PointCloud<PointT>::Ptr
output (
new pcl::PointCloud<PointT>);
359 Eigen::Affine3f inversed_offset = offset.inverse();
360 pcl::transformPointCloud(*input, *output, inversed_offset);
366 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
370 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
387 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
389 Eigen::Affine3f offset = Eigen::Affine3f::Identity();
391 pcl::PointCloud<PointT>::Ptr non_nan_cloud (
new pcl::PointCloud<PointT>);
392 for (
size_t i = 0; i < cloud->points.size(); i++) {
394 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
395 non_nan_cloud->points.push_back(p);
403 const sensor_msgs::PointCloud2::ConstPtr& reference_msg)
412 pcl::PointCloud<PointT>::Ptr reference_cloud (
new pcl::PointCloud<PointT>);
415 pcl::PointCloud<PointT>::Ptr non_nan_reference_cloud (
new pcl::PointCloud<PointT>);
416 for (
size_t i = 0; i < reference_cloud->points.size(); i++) {
417 PointT p = reference_cloud->points[i];
418 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
419 non_nan_reference_cloud->points.push_back(p);
428 pcl::PointCloud<PointT>::Ptr& cloud,
429 const Eigen::Affine3f& offset,
430 const std_msgs::Header&
header)
434 double min_score = DBL_MAX;
436 pcl::PointCloud<PointT>::Ptr best_transformed_cloud;
437 pcl::PointCloud<PointT>::Ptr best_reference;
438 Eigen::Affine3d best_transform_result;
439 Eigen::Affine3f best_offset_result;
440 jsk_recognition_msgs::ICPResult
result;
441 if (cloud->empty()) {
442 sensor_msgs::PointCloud2 empty_cloud;
443 empty_cloud.header =
header;
446 pcl::PointCloud<PointT> empty_pcl_cloud;
451 geometry_msgs::PoseStamped empty_pose;
452 empty_pose.header =
header;
456 result.score = min_score;
461 Eigen::Affine3f offset_result;
462 pcl::PointCloud<PointT>::Ptr transformed_cloud(
new pcl::PointCloud<PointT>);
463 Eigen::Affine3d transform_result;
471 if (score < min_score) {
474 best_transform_result = transform_result;
475 best_transformed_cloud = transformed_cloud;
477 best_offset_result = offset_result;
483 sensor_msgs::PointCloud2 ros_final;
485 ros_final.header =
header;
488 geometry_msgs::PoseStamped ros_result_pose;
489 ros_result_pose.header =
header;
494 pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
495 (
new pcl::PointCloud<PointT>);
496 pcl::transformPointCloud(
497 *best_transformed_cloud, *transformed_cloud_for_debug_result,
498 best_offset_result.inverse());
500 *transformed_cloud_for_debug_result, header);
501 result.header = ros_result_pose.header;
502 result.pose = ros_result_pose.pose;
503 result.score = min_score;
504 std::stringstream ss;
506 result.name = ss.str();
511 const sensor_msgs::CameraInfo::ConstPtr&
msg)
518 pcl::PointCloud<PointT>::Ptr& cloud,
519 pcl::PointCloud<PointT>::Ptr& reference,
520 const Eigen::Affine3f& offset,
521 pcl::PointCloud<PointT>::Ptr& output_cloud,
522 Eigen::Affine3d& output_transform)
534 pcl::PointCloud<PointT>::Ptr& cloud,
535 pcl::PointCloud<PointT>::Ptr& reference,
536 const Eigen::Affine3f& offset,
537 pcl::PointCloud<PointT>::Ptr& output_cloud,
538 Eigen::Affine3d& output_transform)
540 pcl::NormalDistributionsTransform<PointT, PointT> ndt;
541 if (reference->points.empty ()) {
545 ndt.setInputSource(reference);
546 if (cloud->points.empty ()) {
550 ndt.setInputTarget(cloud);
551 pcl::PointCloud<PointT>
final;
553 pcl::transformPointCloud(
final, *output_cloud, offset);
554 Eigen::Matrix4f transformation = ndt.getFinalTransformation ();
555 Eigen::Matrix4d transformation_d;
556 jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
557 transformation, transformation_d);
558 Eigen::Affine3d offsetd;
560 output_transform = offsetd * Eigen::Affine3d(transformation_d);
561 return ndt.getFitnessScore();
565 pcl::PointCloud<PointT>::Ptr& cloud,
566 pcl::PointCloud<PointT>::Ptr& reference,
567 const Eigen::Affine3f& offset,
568 pcl::PointCloud<PointT>::Ptr& output_cloud,
569 Eigen::Affine3d& output_transform)
571 pcl::IterativeClosestPoint<PointT, PointT> icp;
573 pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
574 icp = icp_with_normal;
579 pcl::GeneralizedIterativeClosestPoint<PointT, PointT> gicp;
592 if (!model_success_p) {
596 pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>::Ptr
597 corr_projection (
new pcl::registration::CorrespondenceEstimationOrganizedProjection<PointT, PointT, float>);
598 corr_projection->setFocalLengths(model.
fx(), model.
fy());
599 corr_projection->setCameraCenters(model.
cx(), model.
cy());
600 icp.setCorrespondenceEstimation(corr_projection);
603 if (reference->points.empty ()) {
607 icp.setInputSource(reference);
608 if (cloud->points.empty ()) {
612 icp.setInputTarget(cloud);
616 (
new pcl::registration::WarpPointRigid3D<PointT, PointT>);
618 (
new pcl::registration::TransformationEstimationLM<PointT, PointT>);
619 te->setWarpFunction(warp_func);
620 icp.setTransformationEstimation(te);
629 pcl::PointCloud<PointT>
final;
631 pcl::transformPointCloud(
final, *output_cloud, offset);
634 Eigen::Matrix4f transformation = icp.getFinalTransformation ();
635 Eigen::Matrix4d transformation_d;
636 jsk_recognition_utils::convertMatrix4<Eigen::Matrix4f, Eigen::Matrix4d>(
637 transformation, transformation_d);
638 Eigen::Affine3d offsetd;
640 output_transform = offsetd * Eigen::Affine3d(transformation_d);
641 return icp.getFitnessScore();
646 pcl::PointCloud<PointT>::Ptr& cloud,
647 pcl::PointCloud<PointT>::Ptr& reference,
648 const Eigen::Affine3f& offset,
649 Eigen::Affine3f& offset_result,
650 pcl::PointCloud<PointT>::Ptr transformed_cloud,
651 Eigen::Affine3d& transform_result)
653 pcl::PointCloud<PointT>::Ptr transformed_cloud_for_debug_result
654 (
new pcl::PointCloud<PointT>);
656 transformed_cloud, transform_result);
657 pcl::transformPointCloud(
658 *transformed_cloud, *transformed_cloud_for_debug_result,
660 offset_result = offset;
662 pcl::PointCloud<PointT>::Ptr flipped_transformed_cloud
663 (
new pcl::PointCloud<PointT>);
664 Eigen::Affine3d flipped_transform_result;
665 Eigen::Affine3f flipped_offset
666 = offset * Eigen::AngleAxisf(
M_PI, Eigen::Vector3f(0, 0, 1));
667 pcl::PointCloud<PointT>::Ptr flipped_cloud (
new pcl::PointCloud<PointT>);
668 pcl::transformPointCloud(
669 *cloud, *flipped_cloud,
670 Eigen::Affine3f(Eigen::AngleAxisf(
M_PI, Eigen::Vector3f(0, 0, 1))));
673 flipped_transformed_cloud,
674 flipped_transform_result);
676 if (flipped_score < score) {
677 score = flipped_score;
678 transformed_cloud = flipped_transformed_cloud;
679 transform_result = flipped_transform_result;
680 pcl::transformPointCloud(
681 *transformed_cloud, *transformed_cloud_for_debug_result,
682 flipped_offset.inverse());
683 offset_result = flipped_offset;
690 const sensor_msgs::PointCloud2::ConstPtr&
msg)
698 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
700 pcl::PointCloud<PointT>::Ptr non_nan_cloud (
new pcl::PointCloud<PointT>);
701 for (
size_t i = 0; i < cloud->points.size(); i++) {
703 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
704 non_nan_cloud->points.push_back(p);
711 const jsk_recognition_msgs::PointsArray::ConstPtr&
msg)
719 for (
size_t i = 0; i < msg->cloud_list.size(); i++) {
720 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
727 const sensor_msgs::PointCloud2::ConstPtr&
msg)
735 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
virtual double alignPointcloudWithICP(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)
#define NODELET_ERROR(...)
virtual bool alignService(jsk_recognition_msgs::ICPAlign::Request &req, jsk_recognition_msgs::ICPAlign::Response &res)
bool use_normal_
Store value of ~use_normal. If this parameter is true, ICPRegistration nodelet expects reference and ...
#define NODELET_WARN(...)
ros::Subscriber sub_reference_array_
void publish(const boost::shared_ptr< M > &message) const
virtual double scorePointcloudAlignment(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, Eigen::Affine3f &offset_result, pcl::PointCloud< PointT >::Ptr transformed_cloud, Eigen::Affine3d &transform_result)
virtual void publishDebugCloud(ros::Publisher &pub, const pcl::PointCloud< PointT > &cloud, const std_msgs::Header &header)
ros::Publisher pub_debug_flipped_cloud_
double transform_epsilon_
ros::Publisher pub_icp_result
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
virtual ScopedWallDurationReporter reporter()
virtual void alignWithOffset(const sensor_msgs::PointCloud2::ConstPtr &msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void unsubscribe()
ros::Publisher pub_result_pose_
tf::TransformListener * tf_listener_
ros::Publisher pub_debug_target_cloud_
virtual void align(const sensor_msgs::PointCloud2::ConstPtr &msg)
bool synchronize_reference_
ros::Publisher pub_result_cloud_
ros::ServiceServer srv_icp_align_
ros::Publisher pub_average_time_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_debug_result_cloud_
ros::Subscriber sub_camera_info_
sensor_msgs::CameraInfo::ConstPtr camera_info_msg_
double ndt_outlier_ratio_
virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< message_filters::Synchronizer< ReferenceSyncPolicy > > sync_reference_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
void output(int index, double value)
pcl::PointXYZRGBNormal PointT
jsk_recognition_utils::WallDurationTimer timer_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
ros::Subscriber sub_reference_
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
int maximum_optimizer_iterations_
void convertEigenAffine3(const Eigen::Affine3d &from, Eigen::Affine3f &to)
double euclidean_fittness_epsilon_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual double alignPointcloudWithNDT(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_offset_
int correspondence_randomness_
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_debug_source_cloud_
virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Affine3f &offset, const std_msgs::Header &header)
virtual void referenceArrayCallback(const jsk_recognition_msgs::PointsArray::ConstPtr &msg)
virtual void referenceAddCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
#define NODELET_INFO(...)
std::vector< pcl::PointCloud< PointT >::Ptr > reference_cloud_list_
double correspondence_distance_
uint32_t getNumSubscribers() const
bool use_offset_pose_
set via ~use_offset_pose parameter. default is false.
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)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_input_
boost::shared_ptr< message_filters::Synchronizer< OffsetSyncPolicy > > sync_offset_
bool use_flipped_initial_pose_
double ransac_iterations_
double ransac_outlier_threshold_
int correspondence_algorithm_
bool isSameFrameId(const std::string &a, const std::string &b)
virtual bool alignWithBoxService(jsk_recognition_msgs::ICPAlignWithBox::Request &req, jsk_recognition_msgs::ICPAlignWithBox::Response &res)
ros::ServiceServer srv_icp_align_with_box_
static tf::TransformListener * getInstance()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_reference_
#define NODELET_FATAL(...)
ros::Subscriber sub_reference_add
bool transform_3dof_
set via ~transform_3dof parameter. default is false.
virtual void alignWithBox(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
jsk_pcl_ros::ICPRegistrationConfig Config
ros::Publisher pub_latest_time_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ICPRegistration, nodelet::Nodelet)
virtual double alignPointcloud(pcl::PointCloud< PointT >::Ptr &cloud, pcl::PointCloud< PointT >::Ptr &reference, const Eigen::Affine3f &offset, pcl::PointCloud< PointT >::Ptr &output_cloud, Eigen::Affine3d &output_transform)