Public Types | Protected Member Functions | Protected Attributes
jsk_pcl_ros::HandleEstimator Class Reference

#include <handle_estimator.h>

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

List of all members.

Public Types

enum  HandleType { NO_HANDLE, HANDLE_SMALL_ENOUGH_STAND_ON_PLANE, HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST, HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST }
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::PointCloud2,
jsk_recognition_msgs::BoundingBox > 
SyncPolicy

Protected Member Functions

virtual void estimate (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void estimateHandle (const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void handleSmallEnoughLieOnPlane (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
virtual void handleSmallEnoughStandOnPlane (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void onInit ()
virtual void selectedIndexCallback (const jsk_recognition_msgs::Int32StampedConstPtr &index)
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

int angle_divide_num_
double approach_offset_
double gripper_size_
boost::circular_buffer
< boost::tuple
< geometry_msgs::PoseArray,
geometry_msgs::PoseArray > > 
output_buf
ros::Publisher pub_
ros::Publisher pub_best_
ros::Publisher pub_preapproach_
ros::Publisher pub_selected_
ros::Publisher pub_selected_preapproach_
message_filters::Subscriber
< jsk_recognition_msgs::BoundingBox > 
sub_box_
ros::Subscriber sub_index_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub_input_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_
tf::TransformListenertf_listener_

Detailed Description

Definition at line 58 of file handle_estimator.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > jsk_pcl_ros::HandleEstimator::SyncPolicy

Definition at line 62 of file handle_estimator.h.


Member Enumeration Documentation

Enumerator:
NO_HANDLE 
HANDLE_SMALL_ENOUGH_STAND_ON_PLANE 
HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST 
HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST 

Definition at line 63 of file handle_estimator.h.


Member Function Documentation

void jsk_pcl_ros::HandleEstimator::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const jsk_recognition_msgs::BoundingBox::ConstPtr &  box_msg 
) [protected, virtual]

Definition at line 80 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::estimateHandle ( const HandleType handle_type,
const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const jsk_recognition_msgs::BoundingBox::ConstPtr &  box_msg 
) [protected, virtual]

Definition at line 127 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::handleSmallEnoughLieOnPlane ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const jsk_recognition_msgs::BoundingBox::ConstPtr &  box_msg,
bool  y_longest 
) [protected, virtual]

Definition at line 205 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::handleSmallEnoughStandOnPlane ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg,
const jsk_recognition_msgs::BoundingBox::ConstPtr &  box_msg 
) [protected, virtual]

Definition at line 145 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 45 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::selectedIndexCallback ( const jsk_recognition_msgs::Int32StampedConstPtr &  index) [protected, virtual]

Definition at line 271 of file handle_estimator_nodelet.cpp.

void jsk_pcl_ros::HandleEstimator::subscribe ( ) [protected, virtual]
void jsk_pcl_ros::HandleEstimator::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 99 of file handle_estimator.h.

Definition at line 98 of file handle_estimator.h.

Definition at line 97 of file handle_estimator.h.

boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > jsk_pcl_ros::HandleEstimator::output_buf [protected]

Definition at line 100 of file handle_estimator.h.

Definition at line 91 of file handle_estimator.h.

Definition at line 91 of file handle_estimator.h.

Definition at line 91 of file handle_estimator.h.

Definition at line 91 of file handle_estimator.h.

Definition at line 91 of file handle_estimator.h.

message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> jsk_pcl_ros::HandleEstimator::sub_box_ [protected]

Definition at line 95 of file handle_estimator.h.

Definition at line 92 of file handle_estimator.h.

Definition at line 94 of file handle_estimator.h.

Definition at line 93 of file handle_estimator.h.

Definition at line 96 of file handle_estimator.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:51