Skip to content

Commit 5f08002

Browse files
committed
Rename stage to Grasp Provider
1 parent 232467f commit 5f08002

File tree

2 files changed

+18
-21
lines changed

2 files changed

+18
-21
lines changed

core/include/moveit/task_constructor/stages/deep_grasp_pose.h renamed to core/include/moveit/task_constructor/stages/grasp_provider.h

Lines changed: 17 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -31,35 +31,32 @@
3131
*********************************************************************/
3232

3333
/* Author: Boston Cleek
34-
Desc: Grasp generator stage using deep learning based grasp synthesizers
34+
Desc: Grasp generator stage
3535
*/
3636

3737
#pragma once
3838

39+
#include <functional>
3940
#include <moveit/task_constructor/stages/generate_pose.h>
4041
#include <moveit/task_constructor/stages/action_base.h>
4142
#include <moveit/task_constructor/storage.h>
4243
#include <moveit/task_constructor/marker_tools.h>
4344
#include <rviz_marker_tools/marker_creation.h>
4445
#include <moveit/planning_scene/planning_scene.h>
4546

46-
// #include <memory>
47-
#include <functional>
48-
// #include <iostream>
49-
5047
namespace moveit {
5148
namespace task_constructor {
5249
namespace stages {
5350

54-
constexpr char LOGNAME[] = "deep_grasp_generator";
51+
constexpr char LOGNAME[] = "grasp_provider";
5552

5653
/**
5754
* @brief Generate grasp candidates using deep learning approaches
5855
* @param ActionSpec - action message (action message name + "ACTION")
5956
* @details Interfaces with a deep learning based grasp library using a action client
6057
*/
6158
template <class ActionSpec>
62-
class DeepGraspPose : public GeneratePose, ActionBase<ActionSpec>
59+
class GraspProvider : public GeneratePose, ActionBase<ActionSpec>
6360
{
6461
private:
6562
typedef ActionBase<ActionSpec> ActionBaseT;
@@ -74,7 +71,7 @@ class DeepGraspPose : public GeneratePose, ActionBase<ActionSpec>
7471
* @param server_timeout - connection to server time out (0 is considered infinite timeout)
7572
* @details Initialize the client and connect to server
7673
*/
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",
7875
double goal_timeout = 0.0, double server_timeout = 0.0);
7976

8077
/**
@@ -115,7 +112,7 @@ class DeepGraspPose : public GeneratePose, ActionBase<ActionSpec>
115112
};
116113

117114
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,
119116
double goal_timeout, double server_timeout)
120117
: GeneratePose(stage_name), ActionBaseT(action_name, false, goal_timeout, server_timeout), found_candidates_(false) {
121118
auto& p = properties();
@@ -130,19 +127,19 @@ DeepGraspPose<ActionSpec>::DeepGraspPose(const std::string& action_name, const s
130127
}
131128

132129
template <class ActionSpec>
133-
void DeepGraspPose<ActionSpec>::composeGoal() {
130+
void GraspProvider<ActionSpec>::composeGoal() {
134131
Goal goal;
135132
goal.action_name = ActionBaseT::action_name_;
136133
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));
140137

141138
ROS_INFO_NAMED(LOGNAME, "Goal sent to server: %s", ActionBaseT::action_name_.c_str());
142139
}
143140

144141
template <class ActionSpec>
145-
bool DeepGraspPose<ActionSpec>::monitorGoal() {
142+
bool GraspProvider<ActionSpec>::monitorGoal() {
146143
// monitor timeout
147144
const bool monitor_timeout = ActionBaseT::goal_timeout_ > std::numeric_limits<double>::epsilon() ? true : false;
148145
const double timeout_time = ros::Time::now().toSec() + ActionBaseT::goal_timeout_;
@@ -166,13 +163,13 @@ bool DeepGraspPose<ActionSpec>::monitorGoal() {
166163
}
167164

168165
template <class ActionSpec>
169-
void DeepGraspPose<ActionSpec>::activeCallback() {
166+
void GraspProvider<ActionSpec>::activeCallback() {
170167
ROS_INFO_NAMED(LOGNAME, "Generate grasp goal now active");
171168
found_candidates_ = false;
172169
}
173170

174171
template <class ActionSpec>
175-
void DeepGraspPose<ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedback) {
172+
void GraspProvider<ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedback) {
176173
// each candidate should have a cost
177174
if (feedback->grasp_candidates.size() != feedback->costs.size()) {
178175
ROS_ERROR_NAMED(LOGNAME, "Invalid input: each grasp candidate needs an associated cost");
@@ -190,7 +187,7 @@ void DeepGraspPose<ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedbac
190187
}
191188

192189
template <class ActionSpec>
193-
void DeepGraspPose<ActionSpec>::doneCallback(const actionlib::SimpleClientGoalState& state,
190+
void GraspProvider<ActionSpec>::doneCallback(const actionlib::SimpleClientGoalState& state,
194191
const ResultConstPtr& result) {
195192
if (state == actionlib::SimpleClientGoalState::SUCCEEDED) {
196193
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
201198
}
202199

203200
template <class ActionSpec>
204-
void DeepGraspPose<ActionSpec>::init(const core::RobotModelConstPtr& robot_model) {
201+
void GraspProvider<ActionSpec>::init(const core::RobotModelConstPtr& robot_model) {
205202
InitStageException errors;
206203
try {
207204
GeneratePose::init(robot_model);
@@ -233,7 +230,7 @@ void DeepGraspPose<ActionSpec>::init(const core::RobotModelConstPtr& robot_model
233230
}
234231

235232
template <class ActionSpec>
236-
void DeepGraspPose<ActionSpec>::compute() {
233+
void GraspProvider<ActionSpec>::compute() {
237234
if (upstream_solutions_.empty()) {
238235
return;
239236
}
@@ -272,7 +269,7 @@ void DeepGraspPose<ActionSpec>::compute() {
272269
}
273270

274271
template <class ActionSpec>
275-
void DeepGraspPose<ActionSpec>::onNewSolution(const SolutionBase& s) {
272+
void GraspProvider<ActionSpec>::onNewSolution(const SolutionBase& s) {
276273
planning_scene::PlanningSceneConstPtr scene = s.end()->scene();
277274

278275
const auto& props = properties();

core/src/stages/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ add_library(${PROJECT_NAME}_stages
44

55
${PROJECT_INCLUDE}/stages/action_base.h
66
${PROJECT_INCLUDE}/stages/current_state.h
7-
${PROJECT_INCLUDE}/stages/deep_grasp_pose.h
7+
${PROJECT_INCLUDE}/stages/grasp_provider.h
88
${PROJECT_INCLUDE}/stages/fixed_state.h
99
${PROJECT_INCLUDE}/stages/fixed_cartesian_poses.h
1010
${PROJECT_INCLUDE}/stages/generate_pose.h

0 commit comments

Comments
 (0)