#include <hinted_handle_estimator.h>

Public Types | |
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, geometry_msgs::PointStamped > | SyncPolicy |
Public Member Functions | |
| HintedHandleEstimator () | |
| virtual | ~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 138 of file hinted_handle_estimator.h.
|
inline |
Definition at line 133 of file hinted_handle_estimator.h.
|
virtual |
Definition at line 75 of file hinted_handle_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 101 of file hinted_handle_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 54 of file hinted_handle_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 86 of file hinted_handle_estimator_nodelet.cpp.
|
protectedvirtual |
Definition at line 95 of file hinted_handle_estimator_nodelet.cpp.
| handle_model jsk_pcl_ros::HintedHandleEstimator::handle |
Definition at line 140 of file hinted_handle_estimator.h.
| tf::TransformListener jsk_pcl_ros::HintedHandleEstimator::listener_ |
Definition at line 139 of file hinted_handle_estimator.h.
|
protected |
Definition at line 149 of file hinted_handle_estimator.h.
|
protected |
Definition at line 153 of file hinted_handle_estimator.h.
|
protected |
Definition at line 154 of file hinted_handle_estimator.h.
|
protected |
Definition at line 152 of file hinted_handle_estimator.h.
|
protected |
Definition at line 151 of file hinted_handle_estimator.h.
|
protected |
Definition at line 150 of file hinted_handle_estimator.h.
|
protected |
Definition at line 155 of file hinted_handle_estimator.h.
|
protected |
Definition at line 156 of file hinted_handle_estimator.h.
|
protected |
Definition at line 157 of file hinted_handle_estimator.h.