handle_estimator.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_PCL_ROS_HANDLE_ESTIMATOR_H_
37 #define JSK_PCL_ROS_HANDLE_ESTIMATOR_H_
38 
39 #include <pcl_ros/pcl_nodelet.h>
40 
44 
46 
47 #include <jsk_recognition_msgs/BoundingBox.h>
48 #include "jsk_recognition_msgs/Int32Stamped.h"
49 #include <geometry_msgs/PoseArray.h>
50 
51 #include <boost/circular_buffer.hpp>
52 #include <boost/tuple/tuple.hpp>
53 
55 
56 namespace jsk_pcl_ros
57 {
59  {
60  public:
61  typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2,
62  jsk_recognition_msgs::BoundingBox > SyncPolicy;
64  {
69  };
70 
71  protected:
72  virtual void onInit();
73  virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
74  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
75  virtual void estimateHandle(const HandleType& handle_type,
76  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
77  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
78  virtual void handleSmallEnoughLieOnPlane(
79  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
80  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
81  bool y_longest);
82  virtual void handleSmallEnoughStandOnPlane(
83  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
84  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
85 
86  virtual void selectedIndexCallback( const jsk_recognition_msgs::Int32StampedConstPtr &index);
87 
88  virtual void subscribe();
89  virtual void unsubscribe();
90 
97  double gripper_size_;
100  boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > output_buf;
101  private:
102  };
103 }
104 
105 #endif
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
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_
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_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46