linemod.h
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 
00037 #ifndef JSK_PCL_ROS_LINEMOD_H_
00038 #define JSK_PCL_ROS_LINEMOD_H_
00039 
00040 #include "jsk_recognition_utils/pcl_conversion_util.h"
00041 #include <image_geometry/pinhole_camera_model.h>
00042 #include <jsk_topic_tools/diagnostic_nodelet.h>
00043 #include <pcl/recognition/linemod/line_rgbd.h>
00044 #include <pcl/recognition/color_gradient_modality.h>
00045 #include <pcl/recognition/surface_normal_modality.h>
00046 
00047 #include <jsk_pcl_ros/LINEMODDetectorConfig.h>
00048 #include <sensor_msgs/PointCloud2.h>
00049 #include <sensor_msgs/CameraInfo.h>
00050 #include <dynamic_reconfigure/server.h>
00051 
00052 #include <std_srvs/Empty.h>
00053 #include <message_filters/subscriber.h>
00054 #include <message_filters/time_synchronizer.h>
00055 #include <message_filters/synchronizer.h>
00056 #include <pcl/recognition/linemod.h>
00057 #include <pcl/recognition/color_gradient_modality.h>
00058 #include <pcl/recognition/surface_normal_modality.h>
00059 #include <jsk_recognition_msgs/BoundingBox.h>
00060 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00061 #include <pcl_ros/pcl_nodelet.h>
00062 
00063 namespace jsk_pcl_ros
00064 {
00065   class LINEMODDetector: public jsk_topic_tools::DiagnosticNodelet
00066   {
00067   public:
00068     typedef LINEMODDetectorConfig Config;
00069     LINEMODDetector(): DiagnosticNodelet("LINEMODDetector") {}
00070   protected:
00072     // methods
00074     virtual void onInit();
00075     virtual void subscribe();
00076     virtual void unsubscribe();
00077     virtual void detect(
00078       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00079     virtual void configCallback(
00080       Config& config, uint32_t level);
00081     virtual void computeCenterOfTemplate(
00082       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00083       const pcl::SparseQuantizedMultiModTemplate& linemod_template,
00084       const pcl::LINEMODDetection& linemod_detection,
00085       Eigen::Vector3f& center);
00087     // ROS variables
00089     ros::Subscriber sub_cloud_;
00090     ros::Publisher pub_cloud_;
00091     ros::Publisher pub_detect_mask_;
00092     ros::Publisher pub_pose_;
00093     ros::Publisher pub_original_template_cloud_;
00094     boost::mutex mutex_;
00095     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00096     
00098     // Parameters
00100     std::string template_file_;
00101     double gradient_magnitude_threshold_;
00102     double detection_threshold_;
00103     //pcl::LineRGBD<pcl::PointXYZRGBA> line_rgbd_;
00104     pcl::LINEMOD linemod_;
00105     pcl::PointCloud<pcl::PointXYZRGBA>::Ptr template_cloud_;
00106     std::vector<Eigen::Affine3f> template_poses_;
00107     std::vector<jsk_recognition_msgs::BoundingBox> template_bboxes_;
00108     pcl::ColorGradientModality<pcl::PointXYZRGBA> color_gradient_mod_;
00109     pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_normal_mod_;
00110   private:
00111     
00112   };
00113   
00114   class LINEMODTrainer: public pcl_ros::PCLNodelet
00115   {
00116   public:
00117     typedef boost::shared_ptr<LINEMODTrainer> Ptr;
00118     typedef message_filters::sync_policies::ExactTime<
00119       sensor_msgs::PointCloud2,
00120       PCLIndicesMsg> SyncPolicy;
00121   protected:
00123     // methods
00125     virtual void onInit();
00126     virtual void store(
00127       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00128       const PCLIndicesMsg::ConstPtr& indices_msg);
00129     virtual void subscribeCloud(
00130       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00131     virtual void subscribeCameraInfo(
00132       const sensor_msgs::CameraInfo::ConstPtr& info_msg);
00133     virtual bool startTraining(std_srvs::Empty::Request& req,
00134                                std_srvs::Empty::Response& res);
00135     virtual std::vector<std::string> trainOneData(
00136       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00137       pcl::PointIndices::Ptr mask,
00138       std::string& tempstr,
00139       int i);
00140     virtual void tar(const std::string& directory, const std::string& output);
00141     virtual bool clearData(std_srvs::Empty::Request& req,
00142                            std_srvs::Empty::Response& res);
00143     virtual void trainWithoutViewpointSampling();
00144     virtual void trainWithViewpointSampling();
00145     virtual void organizedPointCloudWithViewPoint(
00146       const Eigen::Affine3f& transform,
00147       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
00148       const image_geometry::PinholeCameraModel& model,
00149       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
00150       pcl::PointIndices& mask);
00151     virtual void generateLINEMODTrainingData(
00152       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00153       pcl::PointIndices::Ptr mask,
00154       pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
00155       pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
00156       pcl::MaskMap& mask_map,
00157       pcl::RegionXY& region);
00159     // variables
00161     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00162     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00163     message_filters::Subscriber<PCLIndicesMsg> sub_indices_;
00164     ros::ServiceServer start_training_srv_;
00165     ros::ServiceServer clear_data_srv_;
00166     ros::Publisher pub_range_image_;
00167     ros::Publisher pub_colored_range_image_;
00168     ros::Publisher pub_sample_cloud_;
00169     ros::Subscriber sub_input_nonsync_;
00170     ros::Subscriber sub_camera_info_nonsync_;
00171     sensor_msgs::CameraInfo::ConstPtr camera_info_;
00172     std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_before_sampling_;
00173     std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_;
00174     std::vector<pcl::PointIndices::Ptr> sample_indices_;
00175     boost::mutex mutex_;
00176     std::string output_file_;
00177     bool sample_viewpoint_;
00178     double sample_viewpoint_angle_step_;
00179     double sample_viewpoint_radius_step_;
00180     double sample_viewpoint_angle_min_;
00181     double sample_viewpoint_radius_min_;
00182     double sample_viewpoint_angle_max_;
00183     double sample_viewpoint_radius_max_;
00184   private:
00185     
00186   };
00187 }
00188 
00189 
00190 #endif


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43