Skip to content

Commit 86466cf

Browse files
committed
clang format
1 parent 708ae00 commit 86466cf

File tree

3 files changed

+12
-17
lines changed

3 files changed

+12
-17
lines changed

moveit_task_constructor_dexnet/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ find_package(catkin REQUIRED COMPONENTS
2727

2828
# System dependencies are found with CMake's conventions
2929
find_package(Eigen3 REQUIRED)
30-
find_package(OpenCV 3.2 REQUIRED)
30+
find_package(OpenCV REQUIRED)
3131

3232
# Service files
3333
add_service_files(

moveit_task_constructor_dexnet/include/moveit_task_constructor_dexnet/grasp_detection.h

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
#include <Eigen/Geometry>
4343

4444
// Action Server
45-
#include <moveit_task_constructor_msgs/SampleGraspPosesAction.h>
45+
#include <grasping_msgs/GraspPlanningAction.h>
4646
#include <actionlib/server/simple_action_server.h>
4747

4848
namespace moveit_task_constructor_dexnet
@@ -107,10 +107,9 @@ class GraspDetection
107107
ros::ServiceClient gqcnn_client_; // gqcnn service client
108108
ros::ServiceClient image_client_; // image saving service client
109109

110-
std::unique_ptr<actionlib::SimpleActionServer<moveit_task_constructor_msgs::SampleGraspPosesAction>>
111-
server_; // action server
112-
moveit_task_constructor_msgs::SampleGraspPosesFeedback feedback_; // action feedback message
113-
moveit_task_constructor_msgs::SampleGraspPosesResult result_; // action result message
110+
std::unique_ptr<actionlib::SimpleActionServer<grasping_msgs::GraspPlanningAction>> server_; // action server
111+
grasping_msgs::GraspPlanningFeedback feedback_; // action feedback message
112+
grasping_msgs::GraspPlanningResult result_; // action result message
114113

115114
std::string goal_name_; // action name
116115
std::string action_name_; // action namespace

moveit_task_constructor_dexnet/src/grasp_detection.cpp

Lines changed: 7 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -78,8 +78,7 @@ void GraspDetection::loadParameters()
7878
void 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

102101
void 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

Comments
 (0)