linemod.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_LINEMOD_H_
38 #define JSK_PCL_ROS_LINEMOD_H_
39 
43 #include <pcl/recognition/linemod/line_rgbd.h>
44 #include <pcl/recognition/color_gradient_modality.h>
45 #include <pcl/recognition/surface_normal_modality.h>
46 
47 #include <jsk_pcl_ros/LINEMODDetectorConfig.h>
48 #include <sensor_msgs/PointCloud2.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include <dynamic_reconfigure/server.h>
51 
52 #include <std_srvs/Empty.h>
56 #include <pcl/recognition/linemod.h>
57 #include <pcl/recognition/color_gradient_modality.h>
58 #include <pcl/recognition/surface_normal_modality.h>
59 #include <jsk_recognition_msgs/BoundingBox.h>
60 #include <jsk_recognition_msgs/BoundingBoxArray.h>
61 #include <pcl_ros/pcl_nodelet.h>
62 #include <yaml-cpp/yaml.h>
63 
64 namespace jsk_pcl_ros
65 {
67  {
68  public:
69  typedef LINEMODDetectorConfig Config;
70  LINEMODDetector(): DiagnosticNodelet("LINEMODDetector") {}
71  protected:
73  // methods
75  virtual void onInit();
76  virtual void subscribe();
77  virtual void unsubscribe();
78  virtual void setTemplate(YAML::Node doc);
79  virtual void detect(
80  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
81  virtual void configCallback(
82  Config& config, uint32_t level);
83  virtual void computeCenterOfTemplate(
84  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
85  const pcl::SparseQuantizedMultiModTemplate& linemod_template,
86  const pcl::LINEMODDetection& linemod_detection,
87  Eigen::Vector3f& center);
89  // ROS variables
98 
100  // Parameters
102  std::string template_file_;
105  //pcl::LineRGBD<pcl::PointXYZRGBA> line_rgbd_;
106  pcl::LINEMOD linemod_;
107  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr template_cloud_;
108  std::vector<Eigen::Affine3f> template_poses_;
109  std::vector<jsk_recognition_msgs::BoundingBox> template_bboxes_;
110  pcl::ColorGradientModality<pcl::PointXYZRGBA> color_gradient_mod_;
111  pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_normal_mod_;
112  private:
113 
114  };
115 
117  {
118  public:
121  sensor_msgs::PointCloud2,
123  protected:
125  // methods
127  virtual void onInit();
128  virtual void store(
129  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
130  const PCLIndicesMsg::ConstPtr& indices_msg);
131  virtual void subscribeCloud(
132  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
133  virtual void subscribeCameraInfo(
134  const sensor_msgs::CameraInfo::ConstPtr& info_msg);
135  virtual bool startTraining(std_srvs::Empty::Request& req,
136  std_srvs::Empty::Response& res);
137  virtual std::vector<std::string> trainOneData(
138  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
139  pcl::PointIndices::Ptr mask,
140  std::string& tempstr,
141  int i);
142  virtual void tar(const std::string& directory, const std::string& output);
143  virtual bool clearData(std_srvs::Empty::Request& req,
144  std_srvs::Empty::Response& res);
145  virtual void trainWithoutViewpointSampling();
146  virtual void trainWithViewpointSampling();
147  virtual void organizedPointCloudWithViewPoint(
148  const Eigen::Affine3f& transform,
149  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
151  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
152  pcl::PointIndices& mask);
153  virtual void generateLINEMODTrainingData(
154  pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
155  pcl::PointIndices::Ptr mask,
156  pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
157  pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
158  pcl::MaskMap& mask_map,
159  pcl::RegionXY& region);
161  // variables
173  sensor_msgs::CameraInfo::ConstPtr camera_info_;
174  std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_before_sampling_;
175  std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_;
176  std::vector<pcl::PointIndices::Ptr> sample_indices_;
178  std::string output_file_;
187  private:
188 
189  };
190 }
191 
192 
193 #endif
std::string template_file_
Definition: linemod.h:102
ros::ServiceServer clear_data_srv_
Definition: linemod.h:167
std::vector< pcl::PointIndices::Ptr > sample_indices_
Definition: linemod.h:176
double sample_viewpoint_radius_max_
Definition: linemod.h:185
virtual void setTemplate(YAML::Node doc)
ros::Subscriber sub_cloud_
Definition: linemod.h:91
ros::Publisher pub_cloud_
Definition: linemod.h:92
std::vector< jsk_recognition_msgs::BoundingBox > template_bboxes_
Definition: linemod.h:109
pcl::ColorGradientModality< pcl::PointXYZRGBA > color_gradient_mod_
Definition: linemod.h:110
ros::Publisher pub_detect_mask_
Definition: linemod.h:93
sensor_msgs::CameraInfo::ConstPtr camera_info_
Definition: linemod.h:173
double sample_viewpoint_angle_min_
Definition: linemod.h:182
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr template_cloud_
Definition: linemod.h:107
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_before_sampling_
Definition: linemod.h:174
double sample_viewpoint_radius_min_
Definition: linemod.h:183
config
ros::Publisher pub_range_image_
Definition: linemod.h:168
virtual void computeCenterOfTemplate(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, const pcl::SparseQuantizedMultiModTemplate &linemod_template, const pcl::LINEMODDetection &linemod_detection, Eigen::Vector3f &center)
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
Definition: linemod.h:165
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: linemod.h:164
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_
Definition: linemod.h:175
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: linemod.h:97
DiagnosticNodelet(const std::string &name)
ros::Subscriber sub_input_nonsync_
Definition: linemod.h:171
ros::Publisher pub_original_template_cloud_
Definition: linemod.h:95
ros::ServiceServer start_training_srv_
Definition: linemod.h:166
ros::Publisher pub_pose_
Definition: linemod.h:94
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: linemod.h:163
boost::shared_ptr< LINEMODTrainer > Ptr
Definition: linemod.h:119
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
doc
ros::Publisher pub_sample_cloud_
Definition: linemod.h:170
ros::Subscriber sub_camera_info_nonsync_
Definition: linemod.h:172
std::string output_file_
Definition: linemod.h:178
boost::mutex mutex
global mutex.
LINEMODDetectorConfig Config
Definition: linemod.h:69
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, PCLIndicesMsg > SyncPolicy
Definition: linemod.h:122
pcl::SurfaceNormalModality< pcl::PointXYZRGBA > surface_normal_mod_
Definition: linemod.h:111
double sample_viewpoint_angle_step_
Definition: linemod.h:180
double sample_viewpoint_angle_max_
Definition: linemod.h:184
virtual void configCallback(Config &config, uint32_t level)
std::vector< Eigen::Affine3f > template_poses_
Definition: linemod.h:108
double gradient_magnitude_threshold_
Definition: linemod.h:103
ros::Publisher pub_colored_range_image_
Definition: linemod.h:169
pcl::PointIndices PCLIndicesMsg
cloud
double sample_viewpoint_radius_step_
Definition: linemod.h:181


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