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/or 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 
54 #include <jsk_topic_tools/connection_based_nodelet.h>
55 
56 namespace jsk_pcl_ros
57 {
58  class HandleEstimator: public jsk_topic_tools::ConnectionBasedNodelet
59  {
60  public:
61  typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2,
62  jsk_recognition_msgs::BoundingBox > SyncPolicy;
63  enum HandleType
64  {
65  NO_HANDLE,
69  };
70  virtual ~HandleEstimator();
71 
72  protected:
73  virtual void onInit();
74  virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
75  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
76  virtual void estimateHandle(const HandleType& handle_type,
77  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
78  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
79  virtual void handleSmallEnoughLieOnPlane(
80  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
81  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
82  bool y_longest);
83  virtual void handleSmallEnoughStandOnPlane(
84  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
85  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg);
86 
87  virtual void selectedIndexCallback( const jsk_recognition_msgs::Int32StampedConstPtr &index);
88 
89  virtual void subscribe();
90  virtual void unsubscribe();
91 
98  double gripper_size_;
99  double approach_offset_;
100  int angle_divide_num_;
101  boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> > output_buf;
102  private:
103  };
104 }
105 
106 #endif
jsk_pcl_ros::HandleEstimator::estimate
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
Definition: handle_estimator_nodelet.cpp:124
jsk_pcl_ros::HandleEstimator::handleSmallEnoughStandOnPlane
virtual void handleSmallEnoughStandOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
Definition: handle_estimator_nodelet.cpp:189
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::HandleEstimator::HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST
@ HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST
Definition: handle_estimator.h:132
jsk_pcl_ros::HandleEstimator::pub_preapproach_
ros::Publisher pub_preapproach_
Definition: handle_estimator.h:156
jsk_pcl_ros::HandleEstimator::handleSmallEnoughLieOnPlane
virtual void handleSmallEnoughLieOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
Definition: handle_estimator_nodelet.cpp:249
jsk_pcl_ros::HandleEstimator::~HandleEstimator
virtual ~HandleEstimator()
Definition: handle_estimator_nodelet.cpp:95
time_synchronizer.h
tf_listener_singleton.h
jsk_pcl_ros::HandleEstimator::pub_selected_preapproach_
ros::Publisher pub_selected_preapproach_
Definition: handle_estimator.h:156
jsk_pcl_ros::HandleEstimator::approach_offset_
double approach_offset_
Definition: handle_estimator.h:163
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::HandleEstimator::HandleType
HandleType
Definition: handle_estimator.h:127
pcl_nodelet.h
jsk_pcl_ros::HandleEstimator::sub_box_
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
Definition: handle_estimator.h:160
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::HandleEstimator::onInit
virtual void onInit()
Definition: handle_estimator_nodelet.cpp:77
subscriber.h
jsk_pcl_ros::HandleEstimator::subscribe
virtual void subscribe()
Definition: handle_estimator_nodelet.cpp:107
jsk_pcl_ros::HandleEstimator::pub_
ros::Publisher pub_
Definition: handle_estimator.h:156
jsk_pcl_ros::HandleEstimator::selectedIndexCallback
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
Definition: handle_estimator_nodelet.cpp:315
jsk_pcl_ros::HandleEstimator::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: handle_estimator.h:159
jsk_pcl_ros::HandleEstimator::tf_listener_
tf::TransformListener * tf_listener_
Definition: handle_estimator.h:161
jsk_pcl_ros::HandleEstimator::NO_HANDLE
@ NO_HANDLE
Definition: handle_estimator.h:129
jsk_pcl_ros::HandleEstimator::angle_divide_num_
int angle_divide_num_
Definition: handle_estimator.h:164
jsk_pcl_ros::HandleEstimator::HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST
@ HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST
Definition: handle_estimator.h:131
jsk_pcl_ros::HandleEstimator::HANDLE_SMALL_ENOUGH_STAND_ON_PLANE
@ HANDLE_SMALL_ENOUGH_STAND_ON_PLANE
Definition: handle_estimator.h:130
jsk_pcl_ros::HandleEstimator::gripper_size_
double gripper_size_
Definition: handle_estimator.h:162
jsk_pcl_ros::HandleEstimator::unsubscribe
virtual void unsubscribe()
Definition: handle_estimator_nodelet.cpp:117
tf::TransformListener
jsk_pcl_ros::HandleEstimator::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::BoundingBox > SyncPolicy
Definition: handle_estimator.h:126
synchronizer.h
jsk_pcl_ros::HandleEstimator::pub_selected_
ros::Publisher pub_selected_
Definition: handle_estimator.h:156
jsk_pcl_ros::HandleEstimator::pub_best_
ros::Publisher pub_best_
Definition: handle_estimator.h:156
jsk_pcl_ros::HandleEstimator::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: handle_estimator.h:158
message_filters::sync_policies::ExactTime
jsk_pcl_ros::HandleEstimator::sub_index_
ros::Subscriber sub_index_
Definition: handle_estimator.h:157
jsk_pcl_ros::HandleEstimator::estimateHandle
virtual void estimateHandle(const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
Definition: handle_estimator_nodelet.cpp:171
jsk_pcl_ros::HandleEstimator::output_buf
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
Definition: handle_estimator.h:165
ros::Subscriber


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44