Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::HintedStickFinder Class Reference

#include <hinted_stick_finder.h>

Inheritance diagram for jsk_pcl_ros::HintedStickFinder:
Inheritance graph
[legend]

Public Types

typedef message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2 > ASyncPolicy
 
typedef HintedStickFinderConfig Config
 

Public Member Functions

 HintedStickFinder ()
 
virtual ~HintedStickFinder ()
 

Protected Member Functions

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 ()
 

Protected Attributes

int cylinder_fitting_trial_
 
double eps_2d_angle_
 
double eps_angle_
 
double filter_distance_
 
sensor_msgs::CameraInfo::ConstPtr latest_camera_info_
 
geometry_msgs::PolygonStamped::ConstPtr latest_hint_
 
int max_iteration_
 
double max_radius_
 
int min_inliers_
 
double min_probability_
 
double min_radius_
 
boost::mutex mutex_
 
bool not_synchronize_
 Run in continuous mode. continuous mode means this nodelet does not synchronize hint and input messages but keep processing with old hint information. More...
 
double outlier_threshold_
 
ros::Publisher pub_coefficients_
 
ros::Publisher pub_cylinder_marker_
 
ros::Publisher pub_cylinder_pose_
 
ros::Publisher pub_inliers_
 
ros::Publisher pub_line_filtered_indices_
 
ros::Publisher pub_line_filtered_normal_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
 
ros::Subscriber sub_no_sync_camera_info_
 
ros::Subscriber sub_no_sync_cloud_
 
ros::Subscriber sub_no_sync_polygon_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
 
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_
 
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > sync_
 
bool use_normal_
 True if use ~input has normal fields. More...
 

Detailed Description

Definition at line 91 of file hinted_stick_finder.h.

Member Typedef Documentation

◆ ASyncPolicy

typedef message_filters::sync_policies::ApproximateTime< geometry_msgs::PolygonStamped, sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> jsk_pcl_ros::HintedStickFinder::ASyncPolicy

Definition at line 129 of file hinted_stick_finder.h.

◆ Config

typedef HintedStickFinderConfig jsk_pcl_ros::HintedStickFinder::Config

Definition at line 130 of file hinted_stick_finder.h.

Constructor & Destructor Documentation

◆ HintedStickFinder()

jsk_pcl_ros::HintedStickFinder::HintedStickFinder ( )
inline

Definition at line 131 of file hinted_stick_finder.h.

◆ ~HintedStickFinder()

jsk_pcl_ros::HintedStickFinder::~HintedStickFinder ( )
virtual

Definition at line 74 of file hinted_stick_finder_nodelet.cpp.

Member Function Documentation

◆ cloudCallback()

void jsk_pcl_ros::HintedStickFinder::cloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
protectedvirtual

Non synchronized message callback for ~input pointcloud.

Definition at line 107 of file hinted_stick_finder_nodelet.cpp.

◆ configCallback()

void jsk_pcl_ros::HintedStickFinder::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 364 of file hinted_stick_finder_nodelet.cpp.

◆ 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

Synchronized message callback.

Definition at line 151 of file hinted_stick_finder_nodelet.cpp.

◆ filterPointCloud()

void jsk_pcl_ros::HintedStickFinder::filterPointCloud ( const pcl::PointCloud< pcl::PointXYZ >::Ptr &  cloud,
const jsk_recognition_utils::ConvexPolygon::Ptr  polygon,
pcl::PointIndices &  output_indices 
)
protectedvirtual

Definition at line 315 of file hinted_stick_finder_nodelet.cpp.

◆ fittingCylinder()

void jsk_pcl_ros::HintedStickFinder::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 
)
protectedvirtual

Definition at line 234 of file hinted_stick_finder_nodelet.cpp.

◆ hintCallback()

void jsk_pcl_ros::HintedStickFinder::hintCallback ( const geometry_msgs::PolygonStamped::ConstPtr &  hint_msg)
protectedvirtual

Non synchronized message callback for ~input/hint/line.

Definition at line 122 of file hinted_stick_finder_nodelet.cpp.

◆ infoCallback()

void jsk_pcl_ros::HintedStickFinder::infoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  info_msg)
protectedvirtual

Non synchronized message callback for ~input/camera_info.

Definition at line 129 of file hinted_stick_finder_nodelet.cpp.

◆ 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

Definition at line 198 of file hinted_stick_finder_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::HintedStickFinder::onInit ( )
protectedvirtual

Definition at line 49 of file hinted_stick_finder_nodelet.cpp.

◆ polygonFromLine()

jsk_recognition_utils::ConvexPolygon::Ptr jsk_pcl_ros::HintedStickFinder::polygonFromLine ( const geometry_msgs::PolygonStamped::ConstPtr &  polygon_msg,
const image_geometry::PinholeCameraModel model,
Eigen::Vector3f a,
Eigen::Vector3f b 
)
protectedvirtual

Definition at line 338 of file hinted_stick_finder_nodelet.cpp.

◆ rejected2DHint()

bool jsk_pcl_ros::HintedStickFinder::rejected2DHint ( const jsk_recognition_utils::Cylinder::Ptr cylinder,
const Eigen::Vector3f a,
const Eigen::Vector3f b 
)
protectedvirtual

Check direction of cylinder in 2-D image coordinate system and if it is larger than eps_2d_angle_, return false.

Parameters
cylinderCylinder object
a3-D ray to start point of 2-D line
b3-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

Definition at line 85 of file hinted_stick_finder_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::HintedStickFinder::unsubscribe ( )
protectedvirtual

Definition at line 137 of file hinted_stick_finder_nodelet.cpp.

Member Data Documentation

◆ cylinder_fitting_trial_

int jsk_pcl_ros::HintedStickFinder::cylinder_fitting_trial_
protected

Definition at line 228 of file hinted_stick_finder.h.

◆ eps_2d_angle_

double jsk_pcl_ros::HintedStickFinder::eps_2d_angle_
protected

Definition at line 230 of file hinted_stick_finder.h.

◆ eps_angle_

double jsk_pcl_ros::HintedStickFinder::eps_angle_
protected

Definition at line 226 of file hinted_stick_finder.h.

◆ filter_distance_

double jsk_pcl_ros::HintedStickFinder::filter_distance_
protected

Definition at line 223 of file hinted_stick_finder.h.

◆ latest_camera_info_

sensor_msgs::CameraInfo::ConstPtr jsk_pcl_ros::HintedStickFinder::latest_camera_info_
protected

Definition at line 243 of file hinted_stick_finder.h.

◆ latest_hint_

geometry_msgs::PolygonStamped::ConstPtr jsk_pcl_ros::HintedStickFinder::latest_hint_
protected

Definition at line 244 of file hinted_stick_finder.h.

◆ max_iteration_

int jsk_pcl_ros::HintedStickFinder::max_iteration_
protected

Definition at line 225 of file hinted_stick_finder.h.

◆ max_radius_

double jsk_pcl_ros::HintedStickFinder::max_radius_
protected

Definition at line 221 of file hinted_stick_finder.h.

◆ min_inliers_

int jsk_pcl_ros::HintedStickFinder::min_inliers_
protected

Definition at line 229 of file hinted_stick_finder.h.

◆ min_probability_

double jsk_pcl_ros::HintedStickFinder::min_probability_
protected

Definition at line 227 of file hinted_stick_finder.h.

◆ min_radius_

double jsk_pcl_ros::HintedStickFinder::min_radius_
protected

Definition at line 222 of file hinted_stick_finder.h.

◆ mutex_

boost::mutex jsk_pcl_ros::HintedStickFinder::mutex_
protected

Definition at line 201 of file hinted_stick_finder.h.

◆ 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

Definition at line 224 of file hinted_stick_finder.h.

◆ pub_coefficients_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_coefficients_
protected

Definition at line 214 of file hinted_stick_finder.h.

◆ pub_cylinder_marker_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_cylinder_marker_
protected

Definition at line 211 of file hinted_stick_finder.h.

◆ pub_cylinder_pose_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_cylinder_pose_
protected

Definition at line 212 of file hinted_stick_finder.h.

◆ pub_inliers_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_inliers_
protected

Definition at line 213 of file hinted_stick_finder.h.

◆ pub_line_filtered_indices_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_line_filtered_indices_
protected

Definition at line 209 of file hinted_stick_finder.h.

◆ pub_line_filtered_normal_

ros::Publisher jsk_pcl_ros::HintedStickFinder::pub_line_filtered_normal_
protected

Definition at line 210 of file hinted_stick_finder.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::HintedStickFinder::srv_
protected

Definition at line 219 of file hinted_stick_finder.h.

◆ sub_cloud_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::HintedStickFinder::sub_cloud_
protected

Definition at line 205 of file hinted_stick_finder.h.

◆ sub_info_

message_filters::Subscriber<sensor_msgs::CameraInfo> jsk_pcl_ros::HintedStickFinder::sub_info_
protected

Definition at line 204 of file hinted_stick_finder.h.

◆ sub_no_sync_camera_info_

ros::Subscriber jsk_pcl_ros::HintedStickFinder::sub_no_sync_camera_info_
protected

Definition at line 217 of file hinted_stick_finder.h.

◆ sub_no_sync_cloud_

ros::Subscriber jsk_pcl_ros::HintedStickFinder::sub_no_sync_cloud_
protected

Definition at line 216 of file hinted_stick_finder.h.

◆ sub_no_sync_polygon_

ros::Subscriber jsk_pcl_ros::HintedStickFinder::sub_no_sync_polygon_
protected

Definition at line 218 of file hinted_stick_finder.h.

◆ sub_normal_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::HintedStickFinder::sub_normal_
protected

Definition at line 206 of file hinted_stick_finder.h.

◆ sub_polygon_

message_filters::Subscriber<geometry_msgs::PolygonStamped> jsk_pcl_ros::HintedStickFinder::sub_polygon_
protected

Definition at line 203 of file hinted_stick_finder.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<ASyncPolicy> > jsk_pcl_ros::HintedStickFinder::sync_
protected

Definition at line 207 of file hinted_stick_finder.h.

◆ use_normal_

bool jsk_pcl_ros::HintedStickFinder::use_normal_
protected

True if use ~input has normal fields.

Definition at line 235 of file hinted_stick_finder.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46