#include <hinted_handle_estimator.h>
| Public Types | |
| typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | SyncPolicy | 
| Public Member Functions | |
| HintedHandleEstimator () | |
| Public Attributes | |
| handle_model | handle | 
| tf::TransformListener | listener_ | 
| Protected Member Functions | |
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const geometry_msgs::PointStampedConstPtr &point_msg) | 
| virtual void | onInit () | 
| virtual void | subscribe () | 
| virtual void | unsubscribe () | 
| Protected Attributes | |
| boost::mutex | mutex_ | 
| ros::Publisher | pub_debug_marker_ | 
| ros::Publisher | pub_debug_marker_array_ | 
| ros::Publisher | pub_handle_ | 
| ros::Publisher | pub_length_ | 
| ros::Publisher | pub_pose_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_cloud_ | 
| message_filters::Subscriber < geometry_msgs::PointStamped > | sub_point_ | 
| boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ | 
Definition at line 130 of file hinted_handle_estimator.h.
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > jsk_pcl_ros::HintedHandleEstimator::SyncPolicy | 
Definition at line 137 of file hinted_handle_estimator.h.
Definition at line 133 of file hinted_handle_estimator.h.
| void jsk_pcl_ros::HintedHandleEstimator::estimate | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud_msg, | 
| const geometry_msgs::PointStampedConstPtr & | point_msg | ||
| ) |  [protected, virtual] | 
Definition at line 90 of file hinted_handle_estimator_nodelet.cpp.
| void jsk_pcl_ros::HintedHandleEstimator::onInit | ( | void | ) |  [protected, virtual] | 
Definition at line 54 of file hinted_handle_estimator_nodelet.cpp.
| void jsk_pcl_ros::HintedHandleEstimator::subscribe | ( | ) |  [protected, virtual] | 
Definition at line 75 of file hinted_handle_estimator_nodelet.cpp.
| void jsk_pcl_ros::HintedHandleEstimator::unsubscribe | ( | ) |  [protected, virtual] | 
Definition at line 84 of file hinted_handle_estimator_nodelet.cpp.
Definition at line 139 of file hinted_handle_estimator.h.
Definition at line 138 of file hinted_handle_estimator.h.
Definition at line 148 of file hinted_handle_estimator.h.
Definition at line 152 of file hinted_handle_estimator.h.
Definition at line 153 of file hinted_handle_estimator.h.
Definition at line 151 of file hinted_handle_estimator.h.
Definition at line 150 of file hinted_handle_estimator.h.
Definition at line 149 of file hinted_handle_estimator.h.
| message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::HintedHandleEstimator::sub_cloud_  [protected] | 
Definition at line 154 of file hinted_handle_estimator.h.
| message_filters::Subscriber<geometry_msgs::PointStamped> jsk_pcl_ros::HintedHandleEstimator::sub_point_  [protected] | 
Definition at line 155 of file hinted_handle_estimator.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::HintedHandleEstimator::sync_  [protected] | 
Definition at line 156 of file hinted_handle_estimator.h.