Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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_pcl_ros/ICPAlignWithBox.h>
00045 #include <jsk_pcl_ros/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
00055 namespace jsk_pcl_ros
00056 {
00057 class ICPRegistration: public jsk_topic_tools::ConnectionBasedNodelet
00058 {
00059 public:
00060 typedef pcl::PointXYZRGBNormal PointT;
00061 typedef jsk_pcl_ros::ICPRegistrationConfig Config;
00062 typedef message_filters::sync_policies::ExactTime<
00063 sensor_msgs::PointCloud2,
00064 jsk_recognition_msgs::BoundingBox > SyncPolicy;
00065 typedef message_filters::sync_policies::ExactTime<
00066 sensor_msgs::PointCloud2,
00067 sensor_msgs::PointCloud2
00068 > ReferenceSyncPolicy;
00069 protected:
00071
00073 virtual void onInit();
00074 virtual void align(const sensor_msgs::PointCloud2::ConstPtr& msg);
00075 virtual void align(const sensor_msgs::PointCloud2::ConstPtr& msg,
00076 const sensor_msgs::PointCloud2::ConstPtr& reference_msg);
00077 virtual void alignWithBox(
00078 const sensor_msgs::PointCloud2::ConstPtr& msg,
00079 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00080 virtual bool alignWithBoxService(
00081 jsk_pcl_ros::ICPAlignWithBox::Request& req,
00082 jsk_pcl_ros::ICPAlignWithBox::Response& res);
00083 virtual bool alignService(
00084 jsk_pcl_ros::ICPAlign::Request& req,
00085 jsk_pcl_ros::ICPAlign::Response& res);
00086 virtual void referenceCallback(
00087 const sensor_msgs::PointCloud2::ConstPtr& msg);
00088 virtual void referenceArrayCallback(
00089 const jsk_recognition_msgs::PointsArray::ConstPtr& msg);
00090 virtual void referenceAddCallback(
00091 const sensor_msgs::PointCloud2::ConstPtr& msg);
00092 virtual void configCallback (Config &config, uint32_t level);
00093 virtual void publishDebugCloud(
00094 ros::Publisher& pub,
00095 const pcl::PointCloud<PointT>& cloud);
00096 virtual double alignPointcloud(
00097 pcl::PointCloud<PointT>::Ptr& cloud,
00098 pcl::PointCloud<PointT>::Ptr& reference,
00099 const Eigen::Affine3f& offset,
00100 pcl::PointCloud<PointT>::Ptr& output_cloud,
00101 Eigen::Affine3d& output_transform);
00102 virtual double alignPointcloudWithICP(
00103 pcl::PointCloud<PointT>::Ptr& cloud,
00104 pcl::PointCloud<PointT>::Ptr& reference,
00105 const Eigen::Affine3f& offset,
00106 pcl::PointCloud<PointT>::Ptr& output_cloud,
00107 Eigen::Affine3d& output_transform);
00108 virtual double alignPointcloudWithNDT(
00109 pcl::PointCloud<PointT>::Ptr& cloud,
00110 pcl::PointCloud<PointT>::Ptr& reference,
00111 const Eigen::Affine3f& offset,
00112 pcl::PointCloud<PointT>::Ptr& output_cloud,
00113 Eigen::Affine3d& output_transform);
00114 virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(
00115 pcl::PointCloud<PointT>::Ptr& cloud,
00116 const Eigen::Affine3f& offset,
00117 const std_msgs::Header& header);
00118 virtual double scorePointcloudAlignment(
00119 pcl::PointCloud<PointT>::Ptr& cloud,
00120 pcl::PointCloud<PointT>::Ptr& reference,
00121 const Eigen::Affine3f& offset,
00122 Eigen::Affine3f& offset_result,
00123 pcl::PointCloud<PointT>::Ptr transformed_cloud,
00124 Eigen::Affine3d& transform_result);
00125 virtual void cameraInfoCallback(
00126 const sensor_msgs::CameraInfo::ConstPtr& msg);
00127 virtual void subscribe();
00128 virtual void unsubscribe();
00129
00131
00133 ros::Subscriber sub_camera_info_;
00134 ros::Subscriber sub_;
00135 ros::Subscriber sub_reference_;
00136 ros::Subscriber sub_reference_add;
00137 ros::Subscriber sub_reference_array_;
00138 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_sync_input_;
00139 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_sync_reference_;
00140 ros::Publisher pub_result_pose_;
00141 ros::Publisher pub_result_cloud_;
00142 ros::Publisher pub_debug_source_cloud_,
00143 pub_debug_target_cloud_,
00144 pub_debug_result_cloud_,
00145 pub_debug_flipped_cloud_;
00146 ros::Publisher pub_icp_result;
00147
00148 ros::ServiceServer srv_icp_align_with_box_;
00149 ros::ServiceServer srv_icp_align_;
00150 bool align_box_;
00151 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00152 boost::mutex mutex_;
00153 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00154 message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> sub_box_;
00155 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00156 boost::shared_ptr<message_filters::Synchronizer<ReferenceSyncPolicy> > sync_reference_;
00157 tf::TransformListener* tf_listener_;
00158
00164 bool use_normal_;
00165
00167
00169 bool synchronize_reference_;
00170 bool use_flipped_initial_pose_;
00171 int algorithm_;
00172 int correspondence_algorithm_;
00173 std::vector<pcl::PointCloud<PointT>::Ptr> reference_cloud_list_;
00174 int max_iteration_;
00175 double correspondence_distance_;
00176 double transform_epsilon_;
00177 double euclidean_fittness_epsilon_;
00178 double ransac_iterations_;
00179 double ransac_outlier_threshold_;
00180 sensor_msgs::CameraInfo::ConstPtr camera_info_msg_;
00181
00183
00185 double rotation_epsilon_;
00186 int correspondence_randomness_;
00187 int maximum_optimizer_iterations_;
00188
00190
00192 double ndt_resolution_;
00193 double ndt_step_size_;
00194 double ndt_outlier_ratio_;
00195 private:
00196
00197 };
00198 }
00199
00200 #endif