icp_registration.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_PCL_ROS_ICP_REGISTRATION_H_
00038 #define JSK_PCL_ROS_ICP_REGISTRATION_H_
00039 
00040 #include <pcl_ros/pcl_nodelet.h>
00041 #include <dynamic_reconfigure/server.h>
00042 #include <jsk_pcl_ros/ICPRegistrationConfig.h>
00043 #include <jsk_recognition_msgs/BoundingBox.h>
00044 #include <jsk_recognition_msgs/ICPAlignWithBox.h>
00045 #include <jsk_recognition_msgs/ICPAlign.h>
00046 #include <jsk_recognition_msgs/ICPResult.h>
00047 #include <message_filters/subscriber.h>
00048 #include <message_filters/time_synchronizer.h>
00049 #include <message_filters/synchronizer.h>
00050 #include "jsk_pcl_ros/tf_listener_singleton.h"
00051 #include <jsk_topic_tools/connection_based_nodelet.h>
00052 #include <jsk_recognition_msgs/PointsArray.h>
00053 #include <sensor_msgs/CameraInfo.h>
00054 #include <jsk_recognition_utils/time_util.h>
00055 #include <std_msgs/Float32.h>
00056 
00057 namespace jsk_pcl_ros
00058 {
00059   class ICPRegistration: public jsk_topic_tools::ConnectionBasedNodelet
00060   {
00061   public:
00062     typedef pcl::PointXYZRGBNormal PointT;
00063     typedef jsk_pcl_ros::ICPRegistrationConfig Config;
00064     typedef message_filters::sync_policies::ExactTime<
00065       sensor_msgs::PointCloud2,
00066       jsk_recognition_msgs::BoundingBox > SyncPolicy;
00067     typedef message_filters::sync_policies::ExactTime<
00068       sensor_msgs::PointCloud2,
00069       geometry_msgs::PoseStamped > OffsetSyncPolicy;
00070     typedef message_filters::sync_policies::ExactTime<
00071       sensor_msgs::PointCloud2,
00072       sensor_msgs::PointCloud2
00073       > ReferenceSyncPolicy;
00074     ICPRegistration(): timer_(10), done_init_(false) { }
00075   protected:
00077     // methosd
00079     virtual void onInit();
00080     virtual void align(const sensor_msgs::PointCloud2::ConstPtr& msg);
00081     virtual void align(const sensor_msgs::PointCloud2::ConstPtr& msg,
00082                        const sensor_msgs::PointCloud2::ConstPtr& reference_msg);
00083     virtual void alignWithBox(
00084       const sensor_msgs::PointCloud2::ConstPtr& msg,
00085       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00086     virtual void alignWithOffset(
00087       const sensor_msgs::PointCloud2::ConstPtr& msg,
00088       const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
00089     virtual bool alignWithBoxService(
00090       jsk_recognition_msgs::ICPAlignWithBox::Request& req, 
00091       jsk_recognition_msgs::ICPAlignWithBox::Response& res);
00092     virtual bool alignService(
00093       jsk_recognition_msgs::ICPAlign::Request& req, 
00094       jsk_recognition_msgs::ICPAlign::Response& res);
00095     virtual void referenceCallback(
00096       const sensor_msgs::PointCloud2::ConstPtr& msg);
00097     virtual void referenceArrayCallback(
00098       const jsk_recognition_msgs::PointsArray::ConstPtr& msg);
00099     virtual void referenceAddCallback(
00100       const sensor_msgs::PointCloud2::ConstPtr& msg);
00101     virtual void configCallback (Config &config, uint32_t level);
00102     virtual void publishDebugCloud(
00103       ros::Publisher& pub,
00104       const pcl::PointCloud<PointT>& cloud);
00105     virtual double alignPointcloud(
00106       pcl::PointCloud<PointT>::Ptr& cloud,
00107       pcl::PointCloud<PointT>::Ptr& reference,
00108       const Eigen::Affine3f& offset,
00109       pcl::PointCloud<PointT>::Ptr& output_cloud,
00110       Eigen::Affine3d& output_transform);
00111     virtual double alignPointcloudWithICP(
00112       pcl::PointCloud<PointT>::Ptr& cloud,
00113       pcl::PointCloud<PointT>::Ptr& reference,
00114       const Eigen::Affine3f& offset,
00115       pcl::PointCloud<PointT>::Ptr& output_cloud,
00116       Eigen::Affine3d& output_transform);
00117     virtual double alignPointcloudWithNDT(
00118       pcl::PointCloud<PointT>::Ptr& cloud,
00119       pcl::PointCloud<PointT>::Ptr& reference,
00120       const Eigen::Affine3f& offset,
00121       pcl::PointCloud<PointT>::Ptr& output_cloud,
00122       Eigen::Affine3d& output_transform);
00123     virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(
00124       pcl::PointCloud<PointT>::Ptr& cloud,
00125       const Eigen::Affine3f& offset,
00126       const std_msgs::Header& header);
00127     virtual double scorePointcloudAlignment(
00128       pcl::PointCloud<PointT>::Ptr& cloud,
00129       pcl::PointCloud<PointT>::Ptr& reference,
00130       const Eigen::Affine3f& offset,
00131       Eigen::Affine3f& offset_result,
00132       pcl::PointCloud<PointT>::Ptr transformed_cloud,
00133       Eigen::Affine3d& transform_result);
00134     virtual void cameraInfoCallback(
00135       const sensor_msgs::CameraInfo::ConstPtr& msg);
00136     virtual void subscribe();
00137     virtual void unsubscribe();
00138     
00140     // ROS variables
00142     ros::Subscriber sub_camera_info_;
00143     ros::Subscriber sub_;
00144     ros::Subscriber sub_reference_;
00145     ros::Subscriber sub_reference_add;
00146     ros::Subscriber sub_reference_array_;
00147     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_sync_input_;
00148     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_sync_reference_;
00149     ros::Publisher pub_result_pose_;
00150     ros::Publisher pub_result_cloud_;
00151     ros::Publisher pub_latest_time_;
00152     ros::Publisher pub_average_time_;
00153     ros::Publisher pub_debug_source_cloud_,
00154       pub_debug_target_cloud_,
00155       pub_debug_result_cloud_,
00156       pub_debug_flipped_cloud_;
00157     ros::Publisher pub_icp_result;
00158     jsk_recognition_utils::WallDurationTimer timer_;
00159     ros::ServiceServer srv_icp_align_with_box_;
00160     ros::ServiceServer srv_icp_align_;
00161     bool align_box_;
00162     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00163     boost::mutex mutex_;
00164     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00165     message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> sub_box_;
00166     message_filters::Subscriber<geometry_msgs::PoseStamped> sub_offset_;
00167     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00168     boost::shared_ptr<message_filters::Synchronizer<OffsetSyncPolicy> >sync_offset_;
00169     boost::shared_ptr<message_filters::Synchronizer<ReferenceSyncPolicy> > sync_reference_;
00170     tf::TransformListener* tf_listener_;
00171     
00176     bool use_offset_pose_;
00177 
00183     bool use_normal_;
00184     
00186     // parameters for ICP
00188     bool synchronize_reference_;
00189     bool use_flipped_initial_pose_;
00190     int algorithm_;
00191     int correspondence_algorithm_;
00192     std::vector<pcl::PointCloud<PointT>::Ptr> reference_cloud_list_;
00193     int max_iteration_;
00194     double correspondence_distance_;
00195     double transform_epsilon_;
00196     double euclidean_fittness_epsilon_;
00197     double ransac_iterations_;
00198     double ransac_outlier_threshold_;
00199     sensor_msgs::CameraInfo::ConstPtr camera_info_msg_;
00200     
00202     // parameters for GICP
00204     double rotation_epsilon_;
00205     int correspondence_randomness_;
00206     int maximum_optimizer_iterations_;
00207 
00209     // parameters for NDT
00211     double ndt_resolution_;
00212     double ndt_step_size_;
00213     double ndt_outlier_ratio_;
00214 
00215     bool done_init_;
00216   private:
00217     
00218   };
00219 }
00220 
00221 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49