@@ -78,8 +78,7 @@ void GraspDetection::loadParameters()
7878void GraspDetection::init ()
7979{
8080 // action server
81- server_.reset (new actionlib::SimpleActionServer<moveit_task_constructor_msgs::SampleGraspPosesAction>(
82- nh_, action_name_, false ));
81+ server_.reset (new actionlib::SimpleActionServer<grasping_msgs::GraspPlanningAction>(nh_, action_name_, false ));
8382 server_->registerGoalCallback (std::bind (&GraspDetection::goalCallback, this ));
8483 server_->registerPreemptCallback (std::bind (&GraspDetection::preemptCallback, this ));
8584 server_->start ();
@@ -101,7 +100,7 @@ void GraspDetection::init()
101100
102101void GraspDetection::goalCallback ()
103102{
104- goal_name_ = server_->acceptNewGoal ()->action_name ;
103+ goal_name_ = server_->acceptNewGoal ()->object . name ;
105104 ROS_INFO_NAMED (LOGNAME, " New goal accepted: %s" , goal_name_.c_str ());
106105
107106 // save images
@@ -159,7 +158,6 @@ void GraspDetection::sampleGrasps()
159158 if (grasp_candidates.empty ())
160159 {
161160 ROS_ERROR_NAMED (LOGNAME, " No grasp candidates found" );
162- result_.grasp_state = " failed" ;
163161 server_->setAborted (result_);
164162 return ;
165163 }
@@ -193,24 +191,22 @@ void GraspDetection::sampleGrasps()
193191 grasp_pose.pose .orientation .z = rot.z ();
194192
195193 // send feedback to action client
196- feedback_.grasp_candidates .emplace_back (grasp_pose);
194+ moveit_msgs::Grasp current_grasp;
195+ current_grasp.grasp_pose = grasp_pose;
197196
198197 // Q_value (probability of success)
199198 // cost = 1.0 - Q_value, to represent cost
200- const double cost = 1.0 - q_values.at (i);
201- // ROS_INFO_NAMED(LOGNAME, "ID: %u Cost: %f", i, cost);
202- feedback_.costs .emplace_back (cost );
199+ current_grasp. grasp_quality = 1.0 - q_values.at (i);
200+
201+ feedback_.grasps .emplace_back (current_grasp );
203202 }
204203
205204 server_->publishFeedback (feedback_);
206- result_.grasp_state = " success" ;
207205 server_->setSucceeded (result_);
208206 }
209-
210207 else
211208 {
212209 ROS_ERROR_NAMED (LOGNAME, " Failed to call gqcnn_grasp service" );
213- result_.grasp_state = " failed" ;
214210 server_->setAborted (result_);
215211 }
216212}
0 commit comments