31
31
*********************************************************************/
32
32
33
33
/* Author: Boston Cleek
34
- Desc: Grasp generator stage using deep learning based grasp synthesizers
34
+ Desc: Grasp generator stage
35
35
*/
36
36
37
37
#pragma once
38
38
39
+ #include < functional>
39
40
#include < moveit/task_constructor/stages/generate_pose.h>
40
41
#include < moveit/task_constructor/stages/action_base.h>
41
42
#include < moveit/task_constructor/storage.h>
42
43
#include < moveit/task_constructor/marker_tools.h>
43
44
#include < rviz_marker_tools/marker_creation.h>
44
45
#include < moveit/planning_scene/planning_scene.h>
45
46
46
- // #include <memory>
47
- #include < functional>
48
- // #include <iostream>
49
-
50
47
namespace moveit {
51
48
namespace task_constructor {
52
49
namespace stages {
53
50
54
- constexpr char LOGNAME[] = " deep_grasp_generator " ;
51
+ constexpr char LOGNAME[] = " grasp_provider " ;
55
52
56
53
/* *
57
54
* @brief Generate grasp candidates using deep learning approaches
58
55
* @param ActionSpec - action message (action message name + "ACTION")
59
56
* @details Interfaces with a deep learning based grasp library using a action client
60
57
*/
61
58
template <class ActionSpec >
62
- class DeepGraspPose : public GeneratePose , ActionBase<ActionSpec>
59
+ class GraspProvider : public GeneratePose , ActionBase<ActionSpec>
63
60
{
64
61
private:
65
62
typedef ActionBase<ActionSpec> ActionBaseT;
@@ -74,7 +71,7 @@ class DeepGraspPose : public GeneratePose, ActionBase<ActionSpec>
74
71
* @param server_timeout - connection to server time out (0 is considered infinite timeout)
75
72
* @details Initialize the client and connect to server
76
73
*/
77
- DeepGraspPose (const std::string& action_name, const std::string& stage_name = " generate grasp pose" ,
74
+ GraspProvider (const std::string& action_name, const std::string& stage_name = " generate grasp pose" ,
78
75
double goal_timeout = 0.0 , double server_timeout = 0.0 );
79
76
80
77
/* *
@@ -115,7 +112,7 @@ class DeepGraspPose : public GeneratePose, ActionBase<ActionSpec>
115
112
};
116
113
117
114
template <class ActionSpec >
118
- DeepGraspPose <ActionSpec>::DeepGraspPose (const std::string& action_name, const std::string& stage_name,
115
+ GraspProvider <ActionSpec>::GraspProvider (const std::string& action_name, const std::string& stage_name,
119
116
double goal_timeout, double server_timeout)
120
117
: GeneratePose(stage_name), ActionBaseT(action_name, false , goal_timeout, server_timeout), found_candidates_(false ) {
121
118
auto & p = properties ();
@@ -130,19 +127,19 @@ DeepGraspPose<ActionSpec>::DeepGraspPose(const std::string& action_name, const s
130
127
}
131
128
132
129
template <class ActionSpec >
133
- void DeepGraspPose <ActionSpec>::composeGoal() {
130
+ void GraspProvider <ActionSpec>::composeGoal() {
134
131
Goal goal;
135
132
goal.action_name = ActionBaseT::action_name_;
136
133
ActionBaseT::clientPtr_->sendGoal (
137
- goal, std::bind (&DeepGraspPose <ActionSpec>::doneCallback, this , std::placeholders::_1, std::placeholders::_2),
138
- std::bind (&DeepGraspPose <ActionSpec>::activeCallback, this ),
139
- std::bind (&DeepGraspPose <ActionSpec>::feedbackCallback, this , std::placeholders::_1));
134
+ goal, std::bind (&GraspProvider <ActionSpec>::doneCallback, this , std::placeholders::_1, std::placeholders::_2),
135
+ std::bind (&GraspProvider <ActionSpec>::activeCallback, this ),
136
+ std::bind (&GraspProvider <ActionSpec>::feedbackCallback, this , std::placeholders::_1));
140
137
141
138
ROS_INFO_NAMED (LOGNAME, " Goal sent to server: %s" , ActionBaseT::action_name_.c_str ());
142
139
}
143
140
144
141
template <class ActionSpec >
145
- bool DeepGraspPose <ActionSpec>::monitorGoal() {
142
+ bool GraspProvider <ActionSpec>::monitorGoal() {
146
143
// monitor timeout
147
144
const bool monitor_timeout = ActionBaseT::goal_timeout_ > std::numeric_limits<double >::epsilon () ? true : false ;
148
145
const double timeout_time = ros::Time::now ().toSec () + ActionBaseT::goal_timeout_;
@@ -166,13 +163,13 @@ bool DeepGraspPose<ActionSpec>::monitorGoal() {
166
163
}
167
164
168
165
template <class ActionSpec >
169
- void DeepGraspPose <ActionSpec>::activeCallback() {
166
+ void GraspProvider <ActionSpec>::activeCallback() {
170
167
ROS_INFO_NAMED (LOGNAME, " Generate grasp goal now active" );
171
168
found_candidates_ = false ;
172
169
}
173
170
174
171
template <class ActionSpec >
175
- void DeepGraspPose <ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedback) {
172
+ void GraspProvider <ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedback) {
176
173
// each candidate should have a cost
177
174
if (feedback->grasp_candidates .size () != feedback->costs .size ()) {
178
175
ROS_ERROR_NAMED (LOGNAME, " Invalid input: each grasp candidate needs an associated cost" );
@@ -190,7 +187,7 @@ void DeepGraspPose<ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedbac
190
187
}
191
188
192
189
template <class ActionSpec >
193
- void DeepGraspPose <ActionSpec>::doneCallback(const actionlib::SimpleClientGoalState& state,
190
+ void GraspProvider <ActionSpec>::doneCallback(const actionlib::SimpleClientGoalState& state,
194
191
const ResultConstPtr& result) {
195
192
if (state == actionlib::SimpleClientGoalState::SUCCEEDED) {
196
193
ROS_INFO_NAMED (LOGNAME, " Found grasp candidates (result): %s" , result->grasp_state .c_str ());
@@ -201,7 +198,7 @@ void DeepGraspPose<ActionSpec>::doneCallback(const actionlib::SimpleClientGoalSt
201
198
}
202
199
203
200
template <class ActionSpec >
204
- void DeepGraspPose <ActionSpec>::init(const core::RobotModelConstPtr& robot_model) {
201
+ void GraspProvider <ActionSpec>::init(const core::RobotModelConstPtr& robot_model) {
205
202
InitStageException errors;
206
203
try {
207
204
GeneratePose::init (robot_model);
@@ -233,7 +230,7 @@ void DeepGraspPose<ActionSpec>::init(const core::RobotModelConstPtr& robot_model
233
230
}
234
231
235
232
template <class ActionSpec >
236
- void DeepGraspPose <ActionSpec>::compute() {
233
+ void GraspProvider <ActionSpec>::compute() {
237
234
if (upstream_solutions_.empty ()) {
238
235
return ;
239
236
}
@@ -272,7 +269,7 @@ void DeepGraspPose<ActionSpec>::compute() {
272
269
}
273
270
274
271
template <class ActionSpec >
275
- void DeepGraspPose <ActionSpec>::onNewSolution(const SolutionBase& s) {
272
+ void GraspProvider <ActionSpec>::onNewSolution(const SolutionBase& s) {
276
273
planning_scene::PlanningSceneConstPtr scene = s.end ()->scene ();
277
274
278
275
const auto & props = properties ();
0 commit comments