Go to the documentation of this file.00001 #include <agile_grasp/grasp_localizer.h>
00002
00003
00004 GraspLocalizer::GraspLocalizer(ros::NodeHandle& node, const std::string& cloud_topic,
00005 const std::string& cloud_frame, int cloud_type, const std::string& svm_file_name,
00006 const Parameters& params)
00007 : cloud_left_(new PointCloud()), cloud_right_(new PointCloud()),
00008 cloud_frame_(cloud_frame), svm_file_name_(svm_file_name), num_clouds_(params.num_clouds_),
00009 num_clouds_received_(0), plots_handles_(params.plots_hands_)
00010 {
00011
00012 if (cloud_type == CLOUD_SIZED)
00013 cloud_sub_ = node.subscribe(cloud_topic, 1, &GraspLocalizer::cloud_sized_callback, this);
00014 else if (cloud_type == POINT_CLOUD_2)
00015 cloud_sub_ = node.subscribe(cloud_topic, 1, &GraspLocalizer::cloud_callback, this);
00016
00017
00018 grasps_pub_ = node.advertise<agile_grasp::Grasps>("grasps", 10);
00019
00020
00021 localization_ = new Localization(params.num_threads_, true, params.plots_hands_);
00022 localization_->setCameraTransforms(params.cam_tf_left_,
00023 params.cam_tf_right_);
00024 localization_->setWorkspace(params.workspace_);
00025 localization_->setNumSamples(params.num_samples_);
00026 localization_->setFingerWidth(params.finger_width_);
00027 localization_->setHandOuterDiameter(params.hand_outer_diameter_);
00028 localization_->setHandDepth(params.hand_depth_);
00029 localization_->setInitBite(params.init_bite_);
00030 localization_->setHandHeight(params.hand_height_);
00031
00032 min_inliers_ = params.min_inliers_;
00033 }
00034
00035
00036 void GraspLocalizer::cloud_callback(const sensor_msgs::PointCloud2ConstPtr& msg)
00037 {
00038 if (num_clouds_received_ == num_clouds_)
00039 return;
00040
00041
00042 if (cloud_frame_.compare(msg->header.frame_id) != 0
00043 && cloud_frame_.compare("/" + msg->header.frame_id) != 0)
00044 {
00045 std::cout << "Input cloud frame " << msg->header.frame_id <<
00046 " is not equal to parameter " << cloud_frame_ << std::endl;
00047 std::exit(EXIT_FAILURE);
00048 }
00049
00050 if (num_clouds_received_ == 0)
00051 pcl::fromROSMsg(*msg, *cloud_left_);
00052 else if (num_clouds_received_ == 1)
00053 pcl::fromROSMsg(*msg, *cloud_right_);
00054 std::cout << "Received cloud # " << num_clouds_received_ << " with " << msg->height * msg->width << " points\n";
00055 num_clouds_received_++;
00056 }
00057
00058
00059 void GraspLocalizer::cloud_sized_callback(const agile_grasp::CloudSized& msg)
00060 {
00061
00062 if (cloud_frame_.compare(msg.cloud.header.frame_id) != 0)
00063 {
00064 std::cout << "Input cloud frame " << msg.cloud.header.frame_id << " is not equal to parameter "
00065 << cloud_frame_ << std::endl;
00066 std::exit(EXIT_FAILURE);
00067 }
00068
00069 pcl::fromROSMsg(msg.cloud, *cloud_left_);
00070 size_left_ = msg.size_left.data;
00071 std::cout << "Received cloud with size_left: " << size_left_ << std::endl;
00072 num_clouds_received_ = 1;
00073 }
00074
00075
00076 void GraspLocalizer::localizeGrasps()
00077 {
00078 ros::Rate rate(1);
00079 std::vector<int> indices(0);
00080
00081 while (ros::ok())
00082 {
00083
00084 if (num_clouds_received_ == num_clouds_)
00085 {
00086
00087 if (num_clouds_ > 1)
00088 {
00089 PointCloud::Ptr cloud(new PointCloud());
00090 *cloud = *cloud_left_ + *cloud_right_;
00091 hands_ = localization_->localizeHands(cloud, cloud_left_->size(), indices, false, false);
00092 }
00093 else
00094 hands_ = localization_->localizeHands(cloud_left_, size_left_, indices, false, false);
00095
00096 antipodal_hands_ = localization_->predictAntipodalHands(hands_, svm_file_name_);
00097 handles_ = localization_->findHandles(antipodal_hands_, min_inliers_, 0.005, plots_handles_);
00098
00099
00100 grasps_pub_.publish(createGraspsMsg(handles_));
00101 ros::Duration(1.0).sleep();
00102
00103
00104 grasps_pub_.publish(createGraspsMsgFromHands(handles_));
00105 ros::Duration(1.0).sleep();
00106
00107
00108 num_clouds_received_ = 0;
00109 }
00110
00111 ros::spinOnce();
00112 rate.sleep();
00113 }
00114 }
00115
00116
00117 agile_grasp::Grasps GraspLocalizer::createGraspsMsg(const std::vector<GraspHypothesis>& hands)
00118 {
00119 agile_grasp::Grasps msg;
00120
00121 for (int i = 0; i < hands.size(); i++)
00122 {
00123 msg.grasps.push_back(createGraspMsg(hands[i]));
00124 }
00125
00126 msg.header.stamp = ros::Time::now();
00127 return msg;
00128 }
00129
00130
00131 agile_grasp::Grasp GraspLocalizer::createGraspMsg(const GraspHypothesis& hand)
00132 {
00133 agile_grasp::Grasp msg;
00134 tf::vectorEigenToMsg(hand.getGraspBottom(), msg.center);
00135 tf::vectorEigenToMsg(hand.getAxis(), msg.axis);
00136 tf::vectorEigenToMsg(hand.getApproach(), msg.approach);
00137 tf::vectorEigenToMsg(hand.getGraspSurface(), msg.surface_center);
00138 msg.width.data = hand.getGraspWidth();
00139 return msg;
00140 }
00141
00142
00143 agile_grasp::Grasps GraspLocalizer::createGraspsMsgFromHands(const std::vector<Handle>& handles)
00144 {
00145 agile_grasp::Grasps msg;
00146 for (int i = 0; i < handles.size(); i++)
00147 {
00148 const std::vector<GraspHypothesis>& hands = handles[i].getHandList();
00149 const std::vector<int>& inliers = handles[i].getInliers();
00150
00151 for (int j = 0; j < inliers.size(); j++)
00152 {
00153 msg.grasps.push_back(createGraspMsg(hands[inliers[j]]));
00154 }
00155 }
00156 msg.header.stamp = ros::Time::now();
00157 std::cout << "Created grasps msg containing " << msg.grasps.size() << " hands\n";
00158 return msg;
00159 }
00160
00161
00162 agile_grasp::Grasps GraspLocalizer::createGraspsMsg(const std::vector<Handle>& handles)
00163 {
00164 agile_grasp::Grasps msg;
00165 for (int i = 0; i < handles.size(); i++)
00166 msg.grasps.push_back(createGraspMsg(handles[i]));
00167 msg.header.stamp = ros::Time::now();
00168 std::cout << "Created grasps msg containing " << msg.grasps.size() << " handles\n";
00169 return msg;
00170 }
00171
00172
00173 agile_grasp::Grasp GraspLocalizer::createGraspMsg(const Handle& handle)
00174 {
00175 agile_grasp::Grasp msg;
00176 tf::vectorEigenToMsg(handle.getCenter(), msg.center);
00177 tf::vectorEigenToMsg(handle.getAxis(), msg.axis);
00178 tf::vectorEigenToMsg(handle.getApproach(), msg.approach);
00179 tf::vectorEigenToMsg(handle.getHandsCenter(), msg.surface_center);
00180 msg.width.data = handle.getWidth();
00181 return msg;
00182 }