Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
00074 virtual void onInit();
00075 virtual void subscribe();
00076 virtual void unsubscribe();
00077 virtual void updateDiagnostic(
00078 diagnostic_updater::DiagnosticStatusWrapper &stat);
00079 virtual void detect(
00080 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00081 virtual void configCallback(
00082 Config& config, uint32_t level);
00083 virtual void computeCenterOfTemplate(
00084 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00085 const pcl::SparseQuantizedMultiModTemplate& linemod_template,
00086 const pcl::LINEMODDetection& linemod_detection,
00087 Eigen::Vector3f& center);
00089
00091 ros::Subscriber sub_cloud_;
00092 ros::Publisher pub_cloud_;
00093 ros::Publisher pub_detect_mask_;
00094 ros::Publisher pub_pose_;
00095 ros::Publisher pub_original_template_cloud_;
00096 boost::mutex mutex_;
00097 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00098
00100
00102 std::string template_file_;
00103 double gradient_magnitude_threshold_;
00104 double detection_threshold_;
00105
00106 pcl::LINEMOD linemod_;
00107 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr template_cloud_;
00108 std::vector<Eigen::Affine3f> template_poses_;
00109 std::vector<jsk_recognition_msgs::BoundingBox> template_bboxes_;
00110 pcl::ColorGradientModality<pcl::PointXYZRGBA> color_gradient_mod_;
00111 pcl::SurfaceNormalModality<pcl::PointXYZRGBA> surface_normal_mod_;
00112 private:
00113
00114 };
00115
00116 class LINEMODTrainer: public pcl_ros::PCLNodelet
00117 {
00118 public:
00119 typedef boost::shared_ptr<LINEMODTrainer> Ptr;
00120 typedef message_filters::sync_policies::ExactTime<
00121 sensor_msgs::PointCloud2,
00122 PCLIndicesMsg> SyncPolicy;
00123 protected:
00125
00127 virtual void onInit();
00128 virtual void store(
00129 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00130 const PCLIndicesMsg::ConstPtr& indices_msg);
00131 virtual void subscribeCloud(
00132 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
00133 virtual void subscribeCameraInfo(
00134 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
00135 virtual bool startTraining(std_srvs::Empty::Request& req,
00136 std_srvs::Empty::Response& res);
00137 virtual std::vector<std::string> trainOneData(
00138 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00139 pcl::PointIndices::Ptr mask,
00140 std::string& tempstr,
00141 int i);
00142 virtual void tar(const std::string& directory, const std::string& output);
00143 virtual bool clearData(std_srvs::Empty::Request& req,
00144 std_srvs::Empty::Response& res);
00145 virtual void trainWithoutViewpointSampling();
00146 virtual void trainWithViewpointSampling();
00147 virtual void organizedPointCloudWithViewPoint(
00148 const Eigen::Affine3f& transform,
00149 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
00150 const image_geometry::PinholeCameraModel& model,
00151 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
00152 pcl::PointIndices& mask);
00153 virtual void generateLINEMODTrainingData(
00154 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
00155 pcl::PointIndices::Ptr mask,
00156 pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
00157 pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
00158 pcl::MaskMap& mask_map,
00159 pcl::RegionXY& region);
00161
00163 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00164 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00165 message_filters::Subscriber<PCLIndicesMsg> sub_indices_;
00166 ros::ServiceServer start_training_srv_;
00167 ros::ServiceServer clear_data_srv_;
00168 ros::Publisher pub_range_image_;
00169 ros::Publisher pub_colored_range_image_;
00170 ros::Publisher pub_sample_cloud_;
00171 ros::Subscriber sub_input_nonsync_;
00172 ros::Subscriber sub_camera_info_nonsync_;
00173 sensor_msgs::CameraInfo::ConstPtr camera_info_;
00174 std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_before_sampling_;
00175 std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr> samples_;
00176 std::vector<pcl::PointIndices::Ptr> sample_indices_;
00177 boost::mutex mutex_;
00178 std::string output_file_;
00179 bool sample_viewpoint_;
00180 double sample_viewpoint_angle_step_;
00181 double sample_viewpoint_radius_step_;
00182 double sample_viewpoint_angle_min_;
00183 double sample_viewpoint_radius_min_;
00184 double sample_viewpoint_angle_max_;
00185 double sample_viewpoint_radius_max_;
00186 private:
00187
00188 };
00189 }
00190
00191
00192 #endif