Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_LINEMOD_H_
38 #define JSK_PCL_ROS_LINEMOD_H_
42 #include <jsk_topic_tools/diagnostic_nodelet.h>
43 #include <pcl/recognition/linemod/line_rgbd.h>
44 #include <pcl/recognition/color_gradient_modality.h>
45 #include <pcl/recognition/surface_normal_modality.h>
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>
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>
62 #include <yaml-cpp/yaml.h>
66 class LINEMODDetector:
public jsk_topic_tools::DiagnosticNodelet
69 typedef LINEMODDetectorConfig
Config;
80 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
82 Config& config, uint32_t level);
84 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
85 const pcl::SparseQuantizedMultiModTemplate& linemod_template,
86 const pcl::LINEMODDetection& linemod_detection,
87 Eigen::Vector3f& center);
121 sensor_msgs::PointCloud2,
130 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
131 const PCLIndicesMsg::ConstPtr& indices_msg);
133 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
135 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
137 std_srvs::Empty::Response&
res);
139 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
140 pcl::PointIndices::Ptr mask,
141 std::string& tempstr,
143 virtual void tar(
const std::string& directory,
const std::string& output);
145 std_srvs::Empty::Response&
res);
149 const Eigen::Affine3f& transform,
150 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr raw_cloud,
152 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
153 pcl::PointIndices& mask);
155 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud,
156 pcl::PointIndices::Ptr mask,
157 pcl::ColorGradientModality<pcl::PointXYZRGBA>& color_grad_mod,
158 pcl::SurfaceNormalModality<pcl::PointXYZRGBA>& surface_norm_mod,
159 pcl::MaskMap& mask_map,
160 pcl::RegionXY& region);
176 std::vector<pcl::PointCloud<pcl::PointXYZRGBA>::Ptr>
samples_;
double sample_viewpoint_angle_min_
std::vector< pcl::PointIndices::Ptr > sample_indices_
ros::Publisher pub_colored_range_image_
sensor_msgs::CameraInfo::ConstPtr camera_info_
ros::Publisher pub_detect_mask_
virtual void subscribeCloud(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
pcl::ColorGradientModality< pcl::PointXYZRGBA > color_gradient_mod_
ros::ServiceServer start_training_srv_
ros::Publisher pub_range_image_
virtual void generateLINEMODTrainingData(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, pcl::PointIndices::Ptr mask, pcl::ColorGradientModality< pcl::PointXYZRGBA > &color_grad_mod, pcl::SurfaceNormalModality< pcl::PointXYZRGBA > &surface_norm_mod, pcl::MaskMap &mask_map, pcl::RegionXY ®ion)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::PointIndices PCLIndicesMsg
virtual bool clearData(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
double sample_viewpoint_angle_max_
virtual void detect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr template_cloud_
double sample_viewpoint_angle_step_
boost::shared_ptr< LINEMODTrainer > Ptr
ros::Publisher pub_sample_cloud_
ros::Subscriber sub_camera_info_nonsync_
virtual void unsubscribe()
virtual void trainWithoutViewpointSampling()
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_
ros::Subscriber sub_input_nonsync_
virtual std::vector< std::string > trainOneData(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, pcl::PointIndices::Ptr mask, std::string &tempstr, int i)
double sample_viewpoint_radius_max_
virtual void configCallback(Config &config, uint32_t level)
std::vector< Eigen::Affine3f > template_poses_
std::vector< pcl::PointCloud< pcl::PointXYZRGBA >::Ptr > samples_before_sampling_
virtual bool startTraining(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
LINEMODDetectorConfig Config
std::vector< jsk_recognition_msgs::BoundingBox > template_bboxes_
virtual void store(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const PCLIndicesMsg::ConstPtr &indices_msg)
double sample_viewpoint_radius_step_
virtual void tar(const std::string &directory, const std::string &output)
virtual void organizedPointCloudWithViewPoint(const Eigen::Affine3f &transform, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr raw_cloud, const image_geometry::PinholeCameraModel &model, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr output, pcl::PointIndices &mask)
virtual void trainWithViewpointSampling()
pcl::SurfaceNormalModality< pcl::PointXYZRGBA > surface_normal_mod_
ros::Subscriber sub_cloud_
double sample_viewpoint_radius_min_
double detection_threshold_
ros::Publisher pub_original_template_cloud_
virtual ~LINEMODTrainer()
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, PCLIndicesMsg > SyncPolicy
boost::mutex mutex
global mutex.
ros::Publisher pub_cloud_
virtual void computeCenterOfTemplate(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud, const pcl::SparseQuantizedMultiModTemplate &linemod_template, const pcl::LINEMODDetection &linemod_detection, Eigen::Vector3f ¢er)
ros::ServiceServer clear_data_srv_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual void setTemplate(YAML::Node doc)
std::string template_file_
double gradient_magnitude_threshold_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void subscribeCameraInfo(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45