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/or 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>
43 #include <jsk_topic_tools/diagnostic_nodelet.h>
47 #include <pcl/visualization/pcl_visualizer.h>
48 #include <std_srvs/Empty.h>
49 
50 namespace jsk_pcl_ros
51 {
52  class CapturedSamplePointCloud
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 
76  class IncrementalModelRegistration: public jsk_topic_tools::DiagnosticNodelet
77  {
78  public:
79  IncrementalModelRegistration(): DiagnosticNodelet("IncrementalModelRegistration") {}
82  sensor_msgs::PointCloud2,
83  pcl_msgs::PointIndices,
84  geometry_msgs::PoseStamped > SyncPolicy;
85  protected:
87  // methods
89  virtual void onInit();
90  virtual void subscribe() {}
91  virtual void unsubscribe() {}
92  virtual void updateDiagnostic(
94  virtual void newsampleCallback(
95  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
96  const pcl_msgs::PointIndices::ConstPtr& indices_msg,
97  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
99  pcl::PointCloud<pcl::PointXYZRGB>::Ptr input,
100  pcl::PointCloud<pcl::PointXYZRGB>::Ptr output,
101  const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
102  virtual bool startRegistration(
103  std_srvs::Empty::Request& req,
104  std_srvs::Empty::Response& res);
105  virtual void callICP(
106  pcl::PointCloud<pcl::PointXYZRGB>::Ptr reference,
107  pcl::PointCloud<pcl::PointXYZRGB>::Ptr target,
108  Eigen::Affine3f& output_transform);
110  // ROS variables
121 
123  // parameters
125  std::vector<CapturedSamplePointCloud::Ptr> samples_;
126  Eigen::Affine3f origin_;
127  pcl::PointCloud<pcl::PointXYZRGB> all_cloud_;
128  std::string frame_id_;
129  private:
130 
131  };
132 }
133 
134 #endif
jsk_pcl_ros::IncrementalModelRegistration::origin_
Eigen::Affine3f origin_
Definition: incremental_model_registration.h:158
ros::Publisher
jsk_pcl_ros::IncrementalModelRegistration::start_registration_srv_
ros::ServiceServer start_registration_srv_
Definition: incremental_model_registration.h:149
boost::shared_ptr
jsk_pcl_ros::IncrementalModelRegistration::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: incremental_model_registration.h:145
jsk_pcl_ros::IncrementalModelRegistration::newsampleCallback
virtual void newsampleCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const pcl_msgs::PointIndices::ConstPtr &indices_msg, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: incremental_model_registration_nodelet.cpp:141
jsk_pcl_ros::CapturedSamplePointCloud::getRefinedPose
virtual Eigen::Affine3f getRefinedPose()
Definition: incremental_model_registration_nodelet.cpp:76
jsk_pcl_ros::IncrementalModelRegistration::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: incremental_model_registration.h:144
jsk_pcl_ros::CapturedSamplePointCloud::original_cloud_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr original_cloud_
Definition: incremental_model_registration.h:132
jsk_pcl_ros::IncrementalModelRegistration::sub_pose_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_pose_
Definition: incremental_model_registration.h:147
time_synchronizer.h
jsk_pcl_ros::IncrementalModelRegistration::samples_
std::vector< CapturedSamplePointCloud::Ptr > samples_
Definition: incremental_model_registration.h:157
jsk_pcl_ros::IncrementalModelRegistration::IncrementalModelRegistration
IncrementalModelRegistration()
Definition: incremental_model_registration.h:111
jsk_pcl_ros::IncrementalModelRegistration::sub_indices_
message_filters::Subscriber< pcl_msgs::PointIndices > sub_indices_
Definition: incremental_model_registration.h:146
jsk_pcl_ros::IncrementalModelRegistration::startRegistration
virtual bool startRegistration(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: incremental_model_registration_nodelet.cpp:206
message_filters::Subscriber< sensor_msgs::PointCloud2 >
ros::ServiceServer
jsk_pcl_ros::IncrementalModelRegistration::mutex_
boost::mutex mutex_
Definition: incremental_model_registration.h:148
jsk_pcl_ros::IncrementalModelRegistration::callICP
virtual void callICP(pcl::PointCloud< pcl::PointXYZRGB >::Ptr reference, pcl::PointCloud< pcl::PointXYZRGB >::Ptr target, Eigen::Affine3f &output_transform)
Definition: incremental_model_registration_nodelet.cpp:185
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::IncrementalModelRegistration::viewer_
boost::shared_ptr< pcl::visualization::PCLVisualizer > viewer_
Definition: incremental_model_registration.h:152
jsk_pcl_ros::IncrementalModelRegistration::unsubscribe
virtual void unsubscribe()
Definition: incremental_model_registration.h:123
jsk_pcl_ros::CapturedSamplePointCloud::setRefinedPose
virtual void setRefinedPose(Eigen::Affine3f pose)
Definition: incremental_model_registration_nodelet.cpp:87
subscriber.h
jsk_pcl_ros::IncrementalModelRegistration::pub_registered_
ros::Publisher pub_registered_
Definition: incremental_model_registration.h:151
jsk_pcl_ros::CapturedSamplePointCloud::original_pose_
Eigen::Affine3f original_pose_
Definition: incremental_model_registration.h:134
jsk_pcl_ros::CapturedSamplePointCloud::getOriginalPose
virtual Eigen::Affine3f getOriginalPose()
Definition: incremental_model_registration_nodelet.cpp:65
jsk_pcl_ros::IncrementalModelRegistration::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: incremental_model_registration.h:124
jsk_pcl_ros::CapturedSamplePointCloud::getRefinedPointCloud
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getRefinedPointCloud()
Definition: incremental_model_registration_nodelet.cpp:71
jsk_pcl_ros::IncrementalModelRegistration::onInit
virtual void onInit()
Definition: incremental_model_registration_nodelet.cpp:93
jsk_pcl_ros::IncrementalModelRegistration::frame_id_
std::string frame_id_
Definition: incremental_model_registration.h:160
jsk_pcl_ros::IncrementalModelRegistration::all_cloud_
pcl::PointCloud< pcl::PointXYZRGB > all_cloud_
Definition: incremental_model_registration.h:159
jsk_pcl_ros::CapturedSamplePointCloud::setRefinedPointCloud
virtual void setRefinedPointCloud(pcl::PointCloud< pcl::PointXYZRGB > cloud)
Definition: incremental_model_registration_nodelet.cpp:81
jsk_pcl_ros::CapturedSamplePointCloud::refined_cloud_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr refined_cloud_
Definition: incremental_model_registration.h:133
synchronizer.h
diagnostic_updater::DiagnosticStatusWrapper
jsk_pcl_ros::CapturedSamplePointCloud::getOriginalPointCloud
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getOriginalPointCloud()
Definition: incremental_model_registration_nodelet.cpp:60
jsk_pcl_ros::IncrementalModelRegistration::pub_cloud_non_registered_
ros::Publisher pub_cloud_non_registered_
Definition: incremental_model_registration.h:150
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::CapturedSamplePointCloud::refined_pose_
Eigen::Affine3f refined_pose_
Definition: incremental_model_registration.h:135
jsk_pcl_ros::IncrementalModelRegistration::~IncrementalModelRegistration
virtual ~IncrementalModelRegistration()
Definition: incremental_model_registration_nodelet.cpp:117
jsk_pcl_ros::IncrementalModelRegistration::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, pcl_msgs::PointIndices, geometry_msgs::PoseStamped > SyncPolicy
Definition: incremental_model_registration.h:116
jsk_pcl_ros::CapturedSamplePointCloud::CapturedSamplePointCloud
CapturedSamplePointCloud()
Definition: incremental_model_registration_nodelet.cpp:46
jsk_pcl_ros::IncrementalModelRegistration::transformPointCloudRepsectedToPose
virtual void transformPointCloudRepsectedToPose(pcl::PointCloud< pcl::PointXYZRGB >::Ptr input, pcl::PointCloud< pcl::PointXYZRGB >::Ptr output, const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
Definition: incremental_model_registration_nodelet.cpp:128
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::CapturedSamplePointCloud::Ptr
boost::shared_ptr< CapturedSamplePointCloud > Ptr
Definition: incremental_model_registration.h:119
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::IncrementalModelRegistration::subscribe
virtual void subscribe()
Definition: incremental_model_registration.h:122
pcl_conversions.h


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44