Go to the documentation of this file.
   37 #ifndef JSK_PCL_ROS_ICP_REGISTRATION_H_ 
   38 #define JSK_PCL_ROS_ICP_REGISTRATION_H_ 
   41 #include <dynamic_reconfigure/server.h> 
   42 #include <jsk_pcl_ros/ICPRegistrationConfig.h> 
   43 #include <jsk_recognition_msgs/BoundingBox.h> 
   44 #include <jsk_recognition_msgs/ICPAlignWithBox.h> 
   45 #include <jsk_recognition_msgs/ICPAlign.h> 
   46 #include <jsk_recognition_msgs/ICPResult.h> 
   51 #include <jsk_topic_tools/connection_based_nodelet.h> 
   52 #include <jsk_recognition_msgs/PointsArray.h> 
   53 #include <sensor_msgs/CameraInfo.h> 
   55 #include <std_msgs/Float32.h> 
   59   class ICPRegistration: 
public jsk_topic_tools::ConnectionBasedNodelet
 
   62     typedef pcl::PointXYZRGBNormal 
PointT;
 
   63     typedef jsk_pcl_ros::ICPRegistrationConfig 
Config;
 
   65       sensor_msgs::PointCloud2,
 
   66       jsk_recognition_msgs::BoundingBox > 
SyncPolicy;
 
   68       sensor_msgs::PointCloud2,
 
   71       sensor_msgs::PointCloud2,
 
   72       sensor_msgs::PointCloud2
 
   81     virtual void align(
const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
   82     virtual void align(
const sensor_msgs::PointCloud2::ConstPtr& 
msg,
 
   83                        const sensor_msgs::PointCloud2::ConstPtr& reference_msg);
 
   85       const sensor_msgs::PointCloud2::ConstPtr& 
msg,
 
   86       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
 
   88       const sensor_msgs::PointCloud2::ConstPtr& 
msg,
 
   89       const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
 
   91       jsk_recognition_msgs::ICPAlignWithBox::Request& 
req, 
 
   92       jsk_recognition_msgs::ICPAlignWithBox::Response& 
res);
 
   94       jsk_recognition_msgs::ICPAlign::Request& 
req, 
 
   95       jsk_recognition_msgs::ICPAlign::Response& 
res);
 
   97       const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
   99       const jsk_recognition_msgs::PointsArray::ConstPtr& 
msg);
 
  101       const sensor_msgs::PointCloud2::ConstPtr& 
msg);
 
  105       const pcl::PointCloud<PointT>& cloud,
 
  106       const std_msgs::Header& 
header);
 
  108       pcl::PointCloud<PointT>::Ptr& cloud,
 
  109       pcl::PointCloud<PointT>::Ptr& reference,
 
  110       const Eigen::Affine3f& offset,
 
  111       pcl::PointCloud<PointT>::Ptr& output_cloud,
 
  112       Eigen::Affine3d& output_transform);
 
  114       pcl::PointCloud<PointT>::Ptr& cloud,
 
  115       pcl::PointCloud<PointT>::Ptr& reference,
 
  116       const Eigen::Affine3f& offset,
 
  117       pcl::PointCloud<PointT>::Ptr& output_cloud,
 
  118       Eigen::Affine3d& output_transform);
 
  120       pcl::PointCloud<PointT>::Ptr& cloud,
 
  121       pcl::PointCloud<PointT>::Ptr& reference,
 
  122       const Eigen::Affine3f& offset,
 
  123       pcl::PointCloud<PointT>::Ptr& output_cloud,
 
  124       Eigen::Affine3d& output_transform);
 
  126       pcl::PointCloud<PointT>::Ptr& cloud,
 
  127       const Eigen::Affine3f& offset,
 
  128       const std_msgs::Header& 
header);
 
  130       pcl::PointCloud<PointT>::Ptr& cloud,
 
  131       pcl::PointCloud<PointT>::Ptr& reference,
 
  132       const Eigen::Affine3f& offset,
 
  133       Eigen::Affine3f& offset_result,
 
  134       pcl::PointCloud<PointT>::Ptr transformed_cloud,
 
  135       Eigen::Affine3d& transform_result);
 
  137       const sensor_msgs::CameraInfo::ConstPtr& 
msg);
 
  
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, geometry_msgs::PoseStamped > OffsetSyncPolicy
ros::Subscriber sub_reference_
double ransac_iterations_
int correspondence_algorithm_
virtual void unsubscribe()
ros::Publisher pub_average_time_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ReferenceSyncPolicy
ros::Subscriber sub_reference_add
boost::shared_ptr< message_filters::Synchronizer< ReferenceSyncPolicy > > sync_reference_
ros::Publisher pub_result_cloud_
std::vector< pcl::PointCloud< PointT >::Ptr > reference_cloud_list_
virtual void configCallback(Config &config, uint32_t level)
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)
double ransac_outlier_threshold_
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 ~ICPRegistration()
virtual void referenceAddCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
bool use_offset_pose_
set via ~use_offset_pose parameter. default is false.
ros::Subscriber sub_camera_info_
virtual void alignWithOffset(const sensor_msgs::PointCloud2::ConstPtr &msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
ros::Publisher pub_debug_target_cloud_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Subscriber sub_reference_array_
virtual void referenceCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
ros::Publisher pub_debug_flipped_cloud_
ros::Publisher pub_debug_result_cloud_
pcl::PointXYZRGBNormal PointT
virtual jsk_recognition_msgs::ICPResult alignPointcloudWithReferences(pcl::PointCloud< PointT >::Ptr &cloud, const Eigen::Affine3f &offset, const std_msgs::Header &header)
ros::ServiceServer srv_icp_align_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
double euclidean_fittness_epsilon_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_offset_
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)
double correspondence_distance_
int maximum_optimizer_iterations_
sensor_msgs::CameraInfo::ConstPtr camera_info_msg_
boost::shared_ptr< message_filters::Synchronizer< OffsetSyncPolicy > > sync_offset_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > SyncPolicy
virtual void alignWithBox(const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void referenceArrayCallback(const jsk_recognition_msgs::PointsArray::ConstPtr &msg)
ros::ServiceServer srv_icp_align_with_box_
bool transform_3dof_
set via ~transform_3dof parameter. default is false.
int correspondence_randomness_
virtual void publishDebugCloud(ros::Publisher &pub, const pcl::PointCloud< PointT > &cloud, const std_msgs::Header &header)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
tf::TransformListener * tf_listener_
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)
jsk_pcl_ros::ICPRegistrationConfig Config
bool synchronize_reference_
double transform_epsilon_
jsk_recognition_utils::WallDurationTimer timer_
bool use_flipped_initial_pose_
virtual void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
ros::Publisher pub_debug_source_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_reference_
boost::mutex mutex
global mutex.
ros::Publisher pub_latest_time_
virtual bool alignService(jsk_recognition_msgs::ICPAlign::Request &req, jsk_recognition_msgs::ICPAlign::Response &res)
virtual bool alignWithBoxService(jsk_recognition_msgs::ICPAlignWithBox::Request &req, jsk_recognition_msgs::ICPAlignWithBox::Response &res)
bool use_normal_
Store value of ~use_normal. If this parameter is true, ICPRegistration nodelet expects reference and ...
virtual void align(const sensor_msgs::PointCloud2::ConstPtr &msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_sync_input_
double ndt_outlier_ratio_
ros::Publisher pub_icp_result
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_result_pose_
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11