Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_PCL_ROS_HANDLE_ESTIMATOR_H_
00037 #define JSK_PCL_ROS_HANDLE_ESTIMATOR_H_
00038
00039 #include <pcl_ros/pcl_nodelet.h>
00040
00041 #include <message_filters/subscriber.h>
00042 #include <message_filters/time_synchronizer.h>
00043 #include <message_filters/synchronizer.h>
00044
00045 #include "jsk_pcl_ros/tf_listener_singleton.h"
00046
00047 #include <jsk_recognition_msgs/BoundingBox.h>
00048 #include "jsk_recognition_msgs/Int32Stamped.h"
00049 #include <geometry_msgs/PoseArray.h>
00050
00051 #include <boost/circular_buffer.hpp>
00052 #include <boost/tuple/tuple.hpp>
00053
00054 #include <jsk_topic_tools/connection_based_nodelet.h>
00055
00056 namespace jsk_pcl_ros
00057 {
00058 class HandleEstimator: public jsk_topic_tools::ConnectionBasedNodelet
00059 {
00060 public:
00061 typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2,
00062 jsk_recognition_msgs::BoundingBox > SyncPolicy;
00063 enum HandleType
00064 {
00065 NO_HANDLE,
00066 HANDLE_SMALL_ENOUGH_STAND_ON_PLANE,
00067 HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST,
00068 HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST
00069 };
00070
00071 protected:
00072 virtual void onInit();
00073 virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00074 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00075 virtual void estimateHandle(const HandleType& handle_type,
00076 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00077 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00078 virtual void handleSmallEnoughLieOnPlane(
00079 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00080 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
00081 bool y_longest);
00082 virtual void handleSmallEnoughStandOnPlane(
00083 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00084 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
00085
00086 virtual void selectedIndexCallback( const jsk_recognition_msgs::Int32StampedConstPtr &index);
00087
00088 virtual void subscribe();
00089 virtual void unsubscribe();
00090
00091 ros::Publisher pub_, pub_best_, pub_preapproach_, pub_selected_, pub_selected_preapproach_;
00092 ros::Subscriber sub_index_;
00093 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00094 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00095 message_filters::Subscriber<jsk_recognition_msgs::BoundingBox> sub_box_;
00096 tf::TransformListener* tf_listener_;
00097 double gripper_size_;
00098 double approach_offset_;
00099 int angle_divide_num_;
00100 boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > output_buf;
00101 private:
00102 };
00103 }
00104
00105 #endif