Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_HINTED_STICK_FINDER_H_
38 #define JSK_PCL_ROS_HINTED_STICK_FINDER_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
47 #include <sensor_msgs/Image.h>
48 #include <geometry_msgs/PolygonStamped.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include <sensor_msgs/PointCloud2.h>
54 #include <dynamic_reconfigure/server.h>
55 #include <jsk_pcl_ros/HintedStickFinderConfig.h>
59 class HintedStickFinder:
public jsk_topic_tools::DiagnosticNodelet
63 geometry_msgs::PolygonStamped,
64 sensor_msgs::CameraInfo,
66 typedef HintedStickFinderConfig
Config;
80 const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
81 const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
82 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
88 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
94 const geometry_msgs::PolygonStamped::ConstPtr& hint_msg);
100 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
103 const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
109 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
111 pcl::PointIndices& output_indices);
113 const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
114 const pcl::PointIndices::Ptr indices,
115 pcl::PointCloud<pcl::Normal>& normals,
116 pcl::PointCloud<pcl::PointXYZ>& normals_cloud);
119 const pcl::PointCloud<pcl::PointXYZ>::Ptr& filtered_cloud,
120 const pcl::PointCloud<pcl::Normal>::Ptr& cloud_nromals,
121 const Eigen::Vector3f& a,
122 const Eigen::Vector3f& b);
134 const Eigen::Vector3f& a,
135 const Eigen::Vector3f& b);
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)
bool use_normal_
True if use ~input has normal fields.
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
Non synchronized message callback for ~input pointcloud.
ros::Publisher pub_line_filtered_indices_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
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_,...
message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > ASyncPolicy
geometry_msgs::PolygonStamped::ConstPtr latest_hint_
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Non synchronized message callback for ~input/camera_info.
ros::Publisher pub_line_filtered_normal_
ros::Publisher pub_coefficients_
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)
double outlier_threshold_
HintedStickFinderConfig Config
ros::Subscriber sub_no_sync_camera_info_
virtual void unsubscribe()
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
virtual void filterPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const jsk_recognition_utils::ConvexPolygon::Ptr polygon, pcl::PointIndices &output_indices)
virtual ~HintedStickFinder()
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
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)
ros::Publisher pub_cylinder_marker_
bool not_synchronize_
Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messag...
ros::Publisher pub_inliers_
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.
int cylinder_fitting_trial_
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
virtual void hintCallback(const geometry_msgs::PolygonStamped::ConstPtr &hint_msg)
Non synchronized message callback for ~input/hint/line.
boost::mutex mutex
global mutex.
ros::Subscriber sub_no_sync_polygon_
ros::Subscriber sub_no_sync_cloud_
ros::Publisher pub_cylinder_pose_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44