incremental_model_registration.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
38 #define JSK_PCL_ROS_INCREMENTAL_MODEL_REGISTRATION_H_
39 
40 #include <geometry_msgs/PoseStamped.h>
41 #include <sensor_msgs/PointCloud.h>
47 #include <pcl/visualization/pcl_visualizer.h>
48 #include <std_srvs/Empty.h>
49 
50 namespace jsk_pcl_ros
51 {
53  {
54  public:
57  CapturedSamplePointCloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
58  const Eigen::Affine3f& original_pose);
59  virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr getOriginalPointCloud();
60  virtual Eigen::Affine3f getOriginalPose();
61  virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr getRefinedPointCloud();
62  virtual Eigen::Affine3f getRefinedPose();
63  virtual void setRefinedPointCloud(
64  pcl::PointCloud<pcl::PointXYZRGB> cloud);
65  virtual void setRefinedPose(Eigen::Affine3f pose);
66 
67  protected:
68  pcl::PointCloud<pcl::PointXYZRGB>::Ptr original_cloud_;
69  pcl::PointCloud<pcl::PointXYZRGB>::Ptr refined_cloud_;
70  Eigen::Affine3f original_pose_;
71  Eigen::Affine3f refined_pose_;
72  private:
73 
74  };
75 
77  {
78  public:
79  IncrementalModelRegistration(): DiagnosticNodelet("IncrementalModelRegistration") {}
81  sensor_msgs::PointCloud2,
82  pcl_msgs::PointIndices,
83  geometry_msgs::PoseStamped > SyncPolicy;
84  protected:
86  // methods
88  virtual void onInit();
89  virtual void subscribe() {}
90  virtual void unsubscribe() {}
91  virtual void updateDiagnostic(
93  virtual void newsampleCallback(
94  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
95  const pcl_msgs::PointIndices::ConstPtr& indices_msg,
96  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
97  virtual void transformPointCloudRepsectedToPose(
98  pcl::PointCloud<pcl::PointXYZRGB>::Ptr input,
99  pcl::PointCloud<pcl::PointXYZRGB>::Ptr output,
100  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
101  virtual bool startRegistration(
102  std_srvs::Empty::Request& req,
103  std_srvs::Empty::Response& res);
104  virtual void callICP(
105  pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference,
106  pcl::PointCloud<pcl::PointXYZRGB>::Ptr target,
107  Eigen::Affine3f& output_transform);
109  // ROS variables
120 
122  // parameters
124  std::vector<CapturedSamplePointCloud::Ptr> samples_;
125  Eigen::Affine3f origin_;
126  pcl::PointCloud<pcl::PointXYZRGB> all_cloud_;
127  std::string frame_id_;
128  private:
129 
130  };
131 }
132 
133 #endif
pcl::PointCloud< pcl::PointXYZRGB >::Ptr original_cloud_
message_filters::Subscriber< pcl_msgs::PointIndices > sub_indices_
virtual void setRefinedPointCloud(pcl::PointCloud< pcl::PointXYZRGB > cloud)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getOriginalPointCloud()
void output(int index, double value)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, pcl_msgs::PointIndices, geometry_msgs::PoseStamped > SyncPolicy
boost::shared_ptr< pcl::visualization::PCLVisualizer > viewer_
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getRefinedPointCloud()
pcl::PointCloud< pcl::PointXYZRGB >::Ptr refined_cloud_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< CapturedSamplePointCloud > Ptr
boost::mutex mutex
global mutex.
std::vector< CapturedSamplePointCloud::Ptr > samples_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46