Skip to content

Commit

Permalink
minor changes
Browse files Browse the repository at this point in the history
  • Loading branch information
jsinapov committed Apr 29, 2017
1 parent 86df139 commit a8c8a92
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion src/agile_grasp/grasp_localizer_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,9 @@ bool GraspLocalizerServer::service_callback(agile_grasp::FindGrasps::Request &re
sensor_msgs::PointCloud2 cloud = req.object_cloud;
pcl::fromROSMsg(cloud, *cloud_left_);

//hand offset approach
//double hand_offset_approach = req.approach_offset;

//compute grasp points
std::vector<int> indices(0);
hands_ = localization_->localizeHands(cloud_left_, cloud_left_->size(), indices, false, false);
Expand All @@ -173,7 +176,7 @@ bool GraspLocalizerServer::service_callback(agile_grasp::FindGrasps::Request &re

for (unsigned int i = 0; i < grasps.grasps.size(); i++){
geometry_msgs::PoseStamped p_grasp_i = graspToPose(grasps.grasps.at(i),HAND_OFFSET_GRASP,req.object_cloud.header.frame_id);
geometry_msgs::PoseStamped p_approach_i = graspToPose(grasps.grasps.at(i),HAND_OFFSET_APPROACH,req.object_cloud.header.frame_id);
geometry_msgs::PoseStamped p_approach_i = graspToPose(grasps.grasps.at(i),HAND_OFFSET_GRASP,req.object_cloud.header.frame_id);

res.grasp_poses.push_back(p_grasp_i);
res.approach_poses.push_back(p_approach_i);
Expand Down

0 comments on commit a8c8a92

Please sign in to comment.