handle_estimator_nodelet.cpp
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 
38 #include <geometry_msgs/PoseArray.h>
39 #include <geometry_msgs/PoseStamped.h>
42 
43 namespace jsk_pcl_ros
44 {
46  {
47  ConnectionBasedNodelet::onInit();
48  output_buf.resize(100);
49 
50  pnh_->param("gripper_size", gripper_size_, 0.08); // defaults to pr2 gripper size
51  pnh_->param("approach_offset", approach_offset_, 0.1); // default to 10 cm
52  pnh_->param("angle_divide_num", angle_divide_num_, 6); // even will be better
53  pub_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output", 1);
54  pub_best_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_best", 1);
55  pub_selected_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_selected", 1);
56 
57  pub_preapproach_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output_preapproach", 1);
58  pub_selected_preapproach_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_selected_preapproach", 1);
59 
61  }
62 
64  {
65  sub_index_ = pnh_->subscribe<jsk_recognition_msgs::Int32Stamped>("selected_index", 1, boost::bind( &HandleEstimator::selectedIndexCallback, this, _1));
66  sub_input_.subscribe(*pnh_, "input", 1);
67  sub_box_.subscribe(*pnh_, "input_box", 1);
68  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
69  sync_->connectInput(sub_input_, sub_box_);
70  sync_->registerCallback(boost::bind(&HandleEstimator::estimate, this, _1, _2));
71  }
72 
74  {
78  }
79 
80  void HandleEstimator::estimate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
81  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
82  {
83  // pack dimensions into vector
84  std::vector<double> dimensions;
85  dimensions.push_back(box_msg->dimensions.x);
86  dimensions.push_back(box_msg->dimensions.y);
87  dimensions.push_back(box_msg->dimensions.z);
88  size_t longest_index = 0;
89  for (size_t i = 1; i < 3; i++) {
90  if (dimensions[i] > dimensions[longest_index]) {
91  longest_index = i;
92  }
93  }
94  NODELET_INFO_STREAM("longest index is: " << longest_index);
95  HandleType handle_type;
96  // detect the handle type
97  if (longest_index == 2) {
98  if (dimensions[0] < gripper_size_ || dimensions[1] < gripper_size_) {
100  }
101  else {
102  handle_type = NO_HANDLE;
103  }
104  }
105  else {
106  if (longest_index == 0) {
107  if (dimensions[1] < gripper_size_ || dimensions[2] < gripper_size_) {
109  }
110  else {
111  handle_type = NO_HANDLE;
112  }
113  }
114  else { // 1
115  if (dimensions[0] < gripper_size_ || dimensions[2] < gripper_size_) {
117  }
118  else {
119  handle_type = NO_HANDLE;
120  }
121  }
122 
123  }
124  estimateHandle(handle_type, cloud_msg, box_msg);
125  }
126 
128  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
129  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
130  {
131  if (handle_type == NO_HANDLE) {
132  NODELET_ERROR("failed to estimate handle");
133  }
134  else if (handle_type == HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST) {
135  handleSmallEnoughLieOnPlane(cloud_msg, box_msg, true);
136  }
137  else if (handle_type == HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST) {
138  handleSmallEnoughLieOnPlane(cloud_msg, box_msg, false);
139  }
140  else if (handle_type == HANDLE_SMALL_ENOUGH_STAND_ON_PLANE) {
141  handleSmallEnoughStandOnPlane(cloud_msg, box_msg);
142  }
143  }
144 
146  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
147  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
148  {
149  geometry_msgs::PoseArray pose_array;
150  geometry_msgs::PoseArray prepose_array;
151  pose_array.header = box_msg->header;
152  prepose_array.header = box_msg->header;
153  Eigen::Affine3d center;
154  tf::poseMsgToEigen(box_msg->pose, center);
155  Eigen::Vector3d z = center.rotation().col(2);
156  Plane p(Eigen::Vector3f(z[0], z[1], z[2]), 0);
157  Eigen::Vector3d ray = center.translation().normalized();
158  Eigen::Vector3d ray_projected;
159  p.project(ray, ray_projected);
160  ray_projected.normalize();
161 
162  Eigen::Matrix3d center_refined_mat;
163  center_refined_mat.col(0) = ray_projected;
164  center_refined_mat.col(2) = z;
165  center_refined_mat.col(1) = z.cross(ray_projected);
166  Eigen::Affine3d center_refined
167  = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(center_refined_mat);
168 
169  const double angle_margin = 0.2;
170  const double start_angle = M_PI / 2.0 + angle_margin;
171  const double end_angle = M_PI + M_PI / 2.0 - angle_margin;
172  for (size_t i = 0; i < angle_divide_num_; i++) {
173  const double theta = (end_angle - start_angle) / angle_divide_num_ * i + start_angle;
174  Eigen::Vector3d offset_vec = Eigen::Vector3d(cos(theta), sin(theta), 0);
175  Eigen::Vector3d pre_approach_pos
176  = (center_refined * (approach_offset_ * offset_vec));
177  Eigen::Matrix3d orientation;
178  Eigen::Vector3d x_vec
179  = (center_refined.translation() - pre_approach_pos).normalized();
180  Eigen::Vector3d y_vec = z.cross(x_vec);
181 
182  orientation.col(0) = x_vec;
183  orientation.col(1) = y_vec;
184  orientation.col(2) = z;
185 
186  Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
187  Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
188  geometry_msgs::Pose ros_prepose;
189  geometry_msgs::Pose ros_pose;
190  tf::poseEigenToMsg(pre_grasp_pose, ros_prepose);
191  tf::poseEigenToMsg(grasp_pose, ros_pose);
192  prepose_array.poses.push_back(ros_prepose);
193  pose_array.poses.push_back(ros_pose);
194  }
195  pub_.publish(pose_array);
196  pub_preapproach_.publish(prepose_array);
197  geometry_msgs::PoseStamped best;
198  best.header = pose_array.header;
199  best.pose = pose_array.poses[pose_array.poses.size() / 2];
200  pub_best_.publish(best);
201 
202  output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
203  }
204 
206  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
207  const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
208  bool y_longest)
209  {
210  geometry_msgs::PoseArray pose_array;
211  geometry_msgs::PoseArray prepose_array;
212  pose_array.header = box_msg->header;
213  prepose_array.header = box_msg->header;
214  // center
215  Eigen::Affine3d center;
216  tf::poseMsgToEigen(box_msg->pose, center);
217  const double angle_margin = 0.2;
218  const double start_angle = angle_margin;
219  const double end_angle = M_PI - angle_margin;
220 
221  for (size_t i = 0; i <= angle_divide_num_; i++) { // angle_divide_num samples
222  const double theta = (end_angle - start_angle) / angle_divide_num_ * i + start_angle;
223  // x-z plane
224  Eigen::Vector3d offset_vec;
225  if (y_longest) {
226  offset_vec = Eigen::Vector3d(sin(theta), 0, cos(theta));
227  }
228  else {
229  offset_vec = Eigen::Vector3d(0, cos(theta), sin(theta));
230  }
231  Eigen::Vector3d pre_approach_pos
232  = (center * (approach_offset_ * offset_vec));
233  // compute unit vectors to construct orientation
234  Eigen::Matrix3d orientation;
235  if (y_longest) {
236  Eigen::Vector3d x_vec
237  = (center.translation() - pre_approach_pos).normalized();
238  Eigen::Vector3d z_vec = center.rotation().col(1);
239  Eigen::Vector3d y_vec = z_vec.cross(x_vec);
240  orientation.col(0) = x_vec;
241  orientation.col(1) = y_vec;
242  orientation.col(2) = z_vec;
243  }
244  else {
245  Eigen::Vector3d x_vec = (center.translation() - pre_approach_pos).normalized();
246  Eigen::Vector3d z_vec = center.rotation().col(0);
247  Eigen::Vector3d y_vec = z_vec.cross(x_vec);
248  orientation.col(0) = x_vec;
249  orientation.col(1) = y_vec;
250  orientation.col(2) = z_vec;
251  }
252 
253  Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
254  Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
255  geometry_msgs::Pose ros_prepose, ros_pose;
256  tf::poseEigenToMsg(pre_grasp_pose, ros_prepose);
257  tf::poseEigenToMsg(grasp_pose, ros_pose);
258  pose_array.poses.push_back(ros_pose);
259  prepose_array.poses.push_back(ros_prepose);
260  }
261  pub_.publish(pose_array);
262  pub_preapproach_.publish(prepose_array);
263  geometry_msgs::PoseStamped best;
264  best.header = pose_array.header;
265  best.pose = pose_array.poses[pose_array.poses.size() / 2];
266  pub_best_.publish(best);
267 
268  output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
269  }
270 
271  void HandleEstimator::selectedIndexCallback( const jsk_recognition_msgs::Int32StampedConstPtr &index){
272  boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> >::iterator it = output_buf.begin();
273  while (it != output_buf.end()) {
274  geometry_msgs::PoseArray pose_array = it->get<0>();
275  geometry_msgs::PoseArray prepose_array = it->get<1>();
276 
277  if(pose_array.header.stamp == index->header.stamp){
278  geometry_msgs::PoseStamped ps;
279  ps.header = pose_array.header;
280  ps.pose = pose_array.poses[index->data];
282 
283  ps.header = prepose_array.header;
284  ps.pose = prepose_array.poses[index->data];
286  break;
287  }
288  ++it;
289  }
290  }
291 }
292 
boost::circular_buffer< boost::tuple< geometry_msgs::PoseArray, geometry_msgs::PoseArray > > output_buf
#define NODELET_INFO_STREAM(...)
#define NODELET_ERROR(...)
virtual void selectedIndexCallback(const jsk_recognition_msgs::Int32StampedConstPtr &index)
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
double cos()
double sin()
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::HandleEstimator, nodelet::Nodelet)
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)
TFSIMD_FORCE_INLINE Vector3 normalized() const
virtual void handleSmallEnoughLieOnPlane(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg, bool y_longest)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
#define M_PI
boost::shared_ptr< ros::NodeHandle > pnh_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
ros::Publisher pub_selected_preapproach_
virtual void project(const Eigen::Vector3f &p, Eigen::Vector3f &output)
virtual void estimateHandle(const HandleType &handle_type, const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::BoundingBox::ConstPtr &box_msg)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< jsk_recognition_msgs::BoundingBox > sub_box_
p
int theta


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