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 #include "jsk_pcl_ros/handle_estimator.h"
00037 #include <pluginlib/class_list_macros.h>
00038 #include <geometry_msgs/PoseArray.h>
00039 #include <geometry_msgs/PoseStamped.h>
00040 #include <eigen_conversions/eigen_msg.h>
00041 #include "jsk_pcl_ros/geo_util.h"
00042
00043 namespace jsk_pcl_ros
00044 {
00045 void HandleEstimator::onInit()
00046 {
00047 ConnectionBasedNodelet::onInit();
00048 output_buf.resize(100);
00049
00050 pnh_->param("gripper_size", gripper_size_, 0.08);
00051 pnh_->param("approach_offset", approach_offset_, 0.1);
00052 pnh_->param("angle_divide_num", angle_divide_num_, 6);
00053 pub_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output", 1);
00054 pub_best_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_best", 1);
00055 pub_selected_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_selected", 1);
00056
00057 pub_preapproach_ = advertise<geometry_msgs::PoseArray>(*pnh_, "output_preapproach", 1);
00058 pub_selected_preapproach_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output_selected_preapproach", 1);
00059
00060 }
00061
00062 void HandleEstimator::subscribe()
00063 {
00064 sub_index_ = pnh_->subscribe<jsk_recognition_msgs::Int32Stamped>("selected_index", 1, boost::bind( &HandleEstimator::selectedIndexCallback, this, _1));
00065 sub_input_.subscribe(*pnh_, "input", 1);
00066 sub_box_.subscribe(*pnh_, "input_box", 1);
00067 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00068 sync_->connectInput(sub_input_, sub_box_);
00069 sync_->registerCallback(boost::bind(&HandleEstimator::estimate, this, _1, _2));
00070 }
00071
00072 void HandleEstimator::unsubscribe()
00073 {
00074 sub_index_.shutdown();
00075 sub_input_.unsubscribe();
00076 sub_box_.unsubscribe();
00077 }
00078
00079 void HandleEstimator::estimate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00080 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00081 {
00082
00083 std::vector<double> dimensions;
00084 dimensions.push_back(box_msg->dimensions.x);
00085 dimensions.push_back(box_msg->dimensions.y);
00086 dimensions.push_back(box_msg->dimensions.z);
00087 size_t longest_index = 0;
00088 for (size_t i = 1; i < 3; i++) {
00089 if (dimensions[i] > dimensions[longest_index]) {
00090 longest_index = i;
00091 }
00092 }
00093 JSK_NODELET_INFO_STREAM("longest index is: " << longest_index);
00094 HandleType handle_type;
00095
00096 if (longest_index == 2) {
00097 if (dimensions[0] < gripper_size_ || dimensions[1] < gripper_size_) {
00098 handle_type = HANDLE_SMALL_ENOUGH_STAND_ON_PLANE;
00099 }
00100 else {
00101 handle_type = NO_HANDLE;
00102 }
00103 }
00104 else {
00105 if (longest_index == 0) {
00106 if (dimensions[1] < gripper_size_ || dimensions[2] < gripper_size_) {
00107 handle_type = HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST;
00108 }
00109 else {
00110 handle_type = NO_HANDLE;
00111 }
00112 }
00113 else {
00114 if (dimensions[0] < gripper_size_ || dimensions[2] < gripper_size_) {
00115 handle_type = HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST;
00116 }
00117 else {
00118 handle_type = NO_HANDLE;
00119 }
00120 }
00121
00122 }
00123 estimateHandle(handle_type, cloud_msg, box_msg);
00124 }
00125
00126 void HandleEstimator::estimateHandle(const HandleType& handle_type,
00127 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00128 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00129 {
00130 if (handle_type == NO_HANDLE) {
00131 JSK_NODELET_ERROR("failed to estimate handle");
00132 }
00133 else if (handle_type == HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_Y_LONGEST) {
00134 handleSmallEnoughLieOnPlane(cloud_msg, box_msg, true);
00135 }
00136 else if (handle_type == HANDLE_SMALL_ENOUGH_LIE_ON_PLANE_X_LONGEST) {
00137 handleSmallEnoughLieOnPlane(cloud_msg, box_msg, false);
00138 }
00139 else if (handle_type == HANDLE_SMALL_ENOUGH_STAND_ON_PLANE) {
00140 handleSmallEnoughStandOnPlane(cloud_msg, box_msg);
00141 }
00142 }
00143
00144 void HandleEstimator::handleSmallEnoughStandOnPlane(
00145 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00146 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg)
00147 {
00148 geometry_msgs::PoseArray pose_array;
00149 geometry_msgs::PoseArray prepose_array;
00150 pose_array.header = box_msg->header;
00151 prepose_array.header = box_msg->header;
00152 Eigen::Affine3d center;
00153 tf::poseMsgToEigen(box_msg->pose, center);
00154 Eigen::Vector3d z = center.rotation().col(2);
00155 Plane p(Eigen::Vector3f(z[0], z[1], z[2]), 0);
00156 Eigen::Vector3d ray = center.translation().normalized();
00157 Eigen::Vector3d ray_projected;
00158 p.project(ray, ray_projected);
00159 ray_projected.normalize();
00160
00161 Eigen::Matrix3d center_refined_mat;
00162 center_refined_mat.col(0) = ray_projected;
00163 center_refined_mat.col(2) = z;
00164 center_refined_mat.col(1) = z.cross(ray_projected);
00165 Eigen::Affine3d center_refined
00166 = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(center_refined_mat);
00167
00168 const double angle_margin = 0.2;
00169 const double start_angle = M_PI / 2.0 + angle_margin;
00170 const double end_angle = M_PI + M_PI / 2.0 - angle_margin;
00171 for (size_t i = 0; i < angle_divide_num_; i++) {
00172 const double theta = (end_angle - start_angle) / angle_divide_num_ * i + start_angle;
00173 Eigen::Vector3d offset_vec = Eigen::Vector3d(cos(theta), sin(theta), 0);
00174 Eigen::Vector3d pre_approach_pos
00175 = (center_refined * (approach_offset_ * offset_vec));
00176 Eigen::Matrix3d orientation;
00177 Eigen::Vector3d x_vec
00178 = (center_refined.translation() - pre_approach_pos).normalized();
00179 Eigen::Vector3d y_vec = z.cross(x_vec);
00180
00181 orientation.col(0) = x_vec;
00182 orientation.col(1) = y_vec;
00183 orientation.col(2) = z;
00184
00185 Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
00186 Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
00187 geometry_msgs::Pose ros_prepose;
00188 geometry_msgs::Pose ros_pose;
00189 tf::poseEigenToMsg(pre_grasp_pose, ros_prepose);
00190 tf::poseEigenToMsg(grasp_pose, ros_pose);
00191 prepose_array.poses.push_back(ros_prepose);
00192 pose_array.poses.push_back(ros_pose);
00193 }
00194 pub_.publish(pose_array);
00195 pub_preapproach_.publish(prepose_array);
00196 geometry_msgs::PoseStamped best;
00197 best.header = pose_array.header;
00198 best.pose = pose_array.poses[pose_array.poses.size() / 2];
00199 pub_best_.publish(best);
00200
00201 output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
00202 }
00203
00204 void HandleEstimator::handleSmallEnoughLieOnPlane(
00205 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00206 const jsk_recognition_msgs::BoundingBox::ConstPtr& box_msg,
00207 bool y_longest)
00208 {
00209 geometry_msgs::PoseArray pose_array;
00210 geometry_msgs::PoseArray prepose_array;
00211 pose_array.header = box_msg->header;
00212 prepose_array.header = box_msg->header;
00213
00214 Eigen::Affine3d center;
00215 tf::poseMsgToEigen(box_msg->pose, center);
00216 const double angle_margin = 0.2;
00217 const double start_angle = angle_margin;
00218 const double end_angle = M_PI - angle_margin;
00219
00220 for (size_t i = 0; i <= angle_divide_num_; i++) {
00221 const double theta = (end_angle - start_angle) / angle_divide_num_ * i + start_angle;
00222
00223 Eigen::Vector3d offset_vec;
00224 if (y_longest) {
00225 offset_vec = Eigen::Vector3d(sin(theta), 0, cos(theta));
00226 }
00227 else {
00228 offset_vec = Eigen::Vector3d(0, cos(theta), sin(theta));
00229 }
00230 Eigen::Vector3d pre_approach_pos
00231 = (center * (approach_offset_ * offset_vec));
00232
00233 Eigen::Matrix3d orientation;
00234 if (y_longest) {
00235 Eigen::Vector3d x_vec
00236 = (center.translation() - pre_approach_pos).normalized();
00237 Eigen::Vector3d z_vec = center.rotation().col(1);
00238 Eigen::Vector3d y_vec = z_vec.cross(x_vec);
00239 orientation.col(0) = x_vec;
00240 orientation.col(1) = y_vec;
00241 orientation.col(2) = z_vec;
00242 }
00243 else {
00244 Eigen::Vector3d x_vec = (center.translation() - pre_approach_pos).normalized();
00245 Eigen::Vector3d z_vec = center.rotation().col(0);
00246 Eigen::Vector3d y_vec = z_vec.cross(x_vec);
00247 orientation.col(0) = x_vec;
00248 orientation.col(1) = y_vec;
00249 orientation.col(2) = z_vec;
00250 }
00251
00252 Eigen::Affine3d pre_grasp_pose = Eigen::Translation3d(pre_approach_pos) * Eigen::Quaterniond(orientation);
00253 Eigen::Affine3d grasp_pose = Eigen::Translation3d(center.translation()) * Eigen::Quaterniond(orientation);
00254 geometry_msgs::Pose ros_prepose, ros_pose;
00255 tf::poseEigenToMsg(pre_grasp_pose, ros_prepose);
00256 tf::poseEigenToMsg(grasp_pose, ros_pose);
00257 pose_array.poses.push_back(ros_pose);
00258 prepose_array.poses.push_back(ros_prepose);
00259 }
00260 pub_.publish(pose_array);
00261 pub_preapproach_.publish(prepose_array);
00262 geometry_msgs::PoseStamped best;
00263 best.header = pose_array.header;
00264 best.pose = pose_array.poses[pose_array.poses.size() / 2];
00265 pub_best_.publish(best);
00266
00267 output_buf.push_front(boost::make_tuple(pose_array, prepose_array));
00268 }
00269
00270 void HandleEstimator::selectedIndexCallback( const jsk_recognition_msgs::Int32StampedConstPtr &index){
00271 boost::circular_buffer<boost::tuple<geometry_msgs::PoseArray, geometry_msgs::PoseArray> >::iterator it = output_buf.begin();
00272 while (it != output_buf.end()) {
00273 geometry_msgs::PoseArray pose_array = it->get<0>();
00274 geometry_msgs::PoseArray prepose_array = it->get<1>();
00275
00276 if(pose_array.header.stamp == index->header.stamp){
00277 geometry_msgs::PoseStamped ps;
00278 ps.header = pose_array.header;
00279 ps.pose = pose_array.poses[index->data];
00280 pub_selected_.publish(ps);
00281
00282 ps.header = prepose_array.header;
00283 ps.pose = prepose_array.poses[index->data];
00284 pub_selected_preapproach_.publish(ps);
00285 break;
00286 }
00287 ++it;
00288 }
00289 }
00290 }
00291
00292 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HandleEstimator, nodelet::Nodelet);