36 #ifndef JSK_PCL_ROS_HANDLE_ESTIMATOR_H_ 37 #define JSK_PCL_ROS_HANDLE_ESTIMATOR_H_ 47 #include <jsk_recognition_msgs/BoundingBox.h> 48 #include "jsk_recognition_msgs/Int32Stamped.h" 49 #include <geometry_msgs/PoseArray.h> 51 #include <boost/circular_buffer.hpp> 52 #include <boost/tuple/tuple.hpp> 73 virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
74 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
76 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
77 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
79 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
80 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
83 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
84 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
100 boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> >
output_buf;
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
ros::Publisher pub_preapproach_
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
virtual void unsubscribe()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > SyncPolicy
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
virtual void handleSmallEnoughStandOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void handleSmallEnoughLieOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
tf::TransformListener * tf_listener_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_selected_preapproach_
ros::Subscriber sub_index_
ros::Publisher pub_selected_
virtual void estimateHandle(const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_