#include <hinted_stick_finder.h>
|  | 
| virtual void | cloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) | 
|  | Non synchronized message callback for ~input pointcloud.  More... 
 | 
|  | 
| virtual void | configCallback (Config &config, uint32_t level) | 
|  | 
| virtual void | detect (const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) | 
|  | Synchronized message callback.  More... 
 | 
|  | 
| virtual void | filterPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const jsk_recognition_utils::ConvexPolygon::Ptr polygon, pcl::PointIndices &output_indices) | 
|  | 
| virtual void | fittingCylinder (const pcl::PointCloud< pcl::PointXYZ >::Ptr &filtered_cloud, const pcl::PointCloud< pcl::Normal >::Ptr &cloud_nromals, const Eigen::Vector3f &a, const Eigen::Vector3f &b) | 
|  | 
| virtual void | hintCallback (const geometry_msgs::PolygonStamped::ConstPtr &hint_msg) | 
|  | Non synchronized message callback for ~input/hint/line.  More... 
 | 
|  | 
| virtual void | infoCallback (const sensor_msgs::CameraInfo::ConstPtr &info_msg) | 
|  | Non synchronized message callback for ~input/camera_info.  More... 
 | 
|  | 
| virtual void | normalEstimate (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::PointIndices::Ptr indices, pcl::PointCloud< pcl::Normal > &normals, pcl::PointCloud< pcl::PointXYZ > &normals_cloud) | 
|  | 
| virtual void | onInit () | 
|  | 
| virtual jsk_recognition_utils::ConvexPolygon::Ptr | polygonFromLine (const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg, const image_geometry::PinholeCameraModel &model, Eigen::Vector3f &a, Eigen::Vector3f &b) | 
|  | 
| virtual bool | rejected2DHint (const jsk_recognition_utils::Cylinder::Ptr &cylinder, const Eigen::Vector3f &a, const Eigen::Vector3f &b) | 
|  | Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_, return false.  More... 
 | 
|  | 
| virtual void | subscribe () | 
|  | 
| virtual void | unsubscribe () | 
|  | 
Definition at line 91 of file hinted_stick_finder.h.
 
◆ ASyncPolicy
◆ Config
◆ HintedStickFinder()
  
  | 
        
          | jsk_pcl_ros::HintedStickFinder::HintedStickFinder | ( |  | ) |  |  | inline | 
 
 
◆ ~HintedStickFinder()
  
  | 
        
          | jsk_pcl_ros::HintedStickFinder::~HintedStickFinder | ( |  | ) |  |  | virtual | 
 
 
◆ cloudCallback()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::cloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg | ) |  |  | protectedvirtual | 
 
 
◆ configCallback()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::configCallback | ( | Config & | config, |  
          |  |  | uint32_t | level |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ detect()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::detect | ( | const geometry_msgs::PolygonStamped::ConstPtr & | polygon_msg, |  
          |  |  | const sensor_msgs::CameraInfo::ConstPtr & | camera_info_msg, |  
          |  |  | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ filterPointCloud()
◆ fittingCylinder()
◆ hintCallback()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::hintCallback | ( | const geometry_msgs::PolygonStamped::ConstPtr & | hint_msg | ) |  |  | protectedvirtual | 
 
 
◆ infoCallback()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::infoCallback | ( | const sensor_msgs::CameraInfo::ConstPtr & | info_msg | ) |  |  | protectedvirtual | 
 
 
◆ normalEstimate()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::normalEstimate | ( | const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, |  
          |  |  | const pcl::PointIndices::Ptr | indices, |  
          |  |  | pcl::PointCloud< pcl::Normal > & | normals, |  
          |  |  | pcl::PointCloud< pcl::PointXYZ > & | normals_cloud |  
          |  | ) |  |  |  | protectedvirtual | 
 
 
◆ onInit()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ polygonFromLine()
◆ rejected2DHint()
Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_, return false. 
- Parameters
- 
  
    | cylinder | Cylinder object |  | a | 3-D ray to start point of 2-D line |  | b | 3-D ray to end point of 2-D line |  
 
Definition at line 218 of file hinted_stick_finder_nodelet.cpp.
 
 
◆ subscribe()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void jsk_pcl_ros::HintedStickFinder::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ cylinder_fitting_trial_
  
  | 
        
          | int jsk_pcl_ros::HintedStickFinder::cylinder_fitting_trial_ |  | protected | 
 
 
◆ eps_2d_angle_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::eps_2d_angle_ |  | protected | 
 
 
◆ eps_angle_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::eps_angle_ |  | protected | 
 
 
◆ filter_distance_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::filter_distance_ |  | protected | 
 
 
◆ latest_camera_info_
  
  | 
        
          | sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::HintedStickFinder::latest_camera_info_ |  | protected | 
 
 
◆ latest_hint_
  
  | 
        
          | geometry_msgs::PolygonStamped::ConstPtr jsk_pcl_ros::HintedStickFinder::latest_hint_ |  | protected | 
 
 
◆ max_iteration_
  
  | 
        
          | int jsk_pcl_ros::HintedStickFinder::max_iteration_ |  | protected | 
 
 
◆ max_radius_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::max_radius_ |  | protected | 
 
 
◆ min_inliers_
  
  | 
        
          | int jsk_pcl_ros::HintedStickFinder::min_inliers_ |  | protected | 
 
 
◆ min_probability_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::min_probability_ |  | protected | 
 
 
◆ min_radius_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::min_radius_ |  | protected | 
 
 
◆ mutex_
◆ not_synchronize_
  
  | 
        
          | bool jsk_pcl_ros::HintedStickFinder::not_synchronize_ |  | protected | 
 
Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messages but keep processing with old hint information. 
Definition at line 241 of file hinted_stick_finder.h.
 
 
◆ outlier_threshold_
  
  | 
        
          | double jsk_pcl_ros::HintedStickFinder::outlier_threshold_ |  | protected | 
 
 
◆ pub_coefficients_
◆ pub_cylinder_marker_
◆ pub_cylinder_pose_
◆ pub_inliers_
◆ pub_line_filtered_indices_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_line_filtered_indices_ |  | protected | 
 
 
◆ pub_line_filtered_normal_
  
  | 
        
          | ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_line_filtered_normal_ |  | protected | 
 
 
◆ srv_
◆ sub_cloud_
◆ sub_info_
◆ sub_no_sync_camera_info_
◆ sub_no_sync_cloud_
◆ sub_no_sync_polygon_
◆ sub_normal_
◆ sub_polygon_
◆ sync_
◆ use_normal_
  
  | 
        
          | bool jsk_pcl_ros::HintedStickFinder::use_normal_ |  | protected | 
 
 
The documentation for this class was generated from the following files: