Go to the documentation of this file.
   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> 
   54 #include <jsk_topic_tools/connection_based_nodelet.h> 
   58   class HandleEstimator: 
public jsk_topic_tools::ConnectionBasedNodelet
 
   62                                                        jsk_recognition_msgs::BoundingBox > 
SyncPolicy;
 
   74     virtual void estimate(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
   75                           const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
 
   77                                 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
   78                                 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
 
   80       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
   81       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
 
   84       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
   85       const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
 
  101     boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > 
output_buf;
 
  
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)
@ HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST
ros::Publisher pub_preapproach_
virtual void handleSmallEnoughLieOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
virtual ~HandleEstimator()
ros::Publisher pub_selected_preapproach_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
tf::TransformListener * tf_listener_
@ HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST
@ HANDLE_SMALL_ENOUGH_STAND_ON_PLANE
virtual void unsubscribe()
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > SyncPolicy
ros::Publisher pub_selected_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Subscriber sub_index_
virtual void estimateHandle(const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11