Skip to content

Commit ae376b6

Browse files
bostoncleekv4hn
authored andcommitted
Remove template paramete to action base class
The action base class can only be used with the action msg GraspPlanning.action from grasping_msgs.
1 parent 19fb72c commit ae376b6

File tree

10 files changed

+301
-261
lines changed

10 files changed

+301
-261
lines changed

core/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ find_package(catkin REQUIRED COMPONENTS
66
actionlib
77
eigen_conversions
88
geometry_msgs
9+
grasping_msgs
910
moveit_core
1011
moveit_ros_planning
1112
moveit_ros_planning_interface
@@ -23,7 +24,9 @@ catkin_package(
2324
INCLUDE_DIRS
2425
include
2526
CATKIN_DEPENDS
27+
actionlib
2628
geometry_msgs
29+
grasping_msgs
2730
moveit_core
2831
moveit_task_constructor_msgs
2932
rviz_marker_tools

core/include/moveit/task_constructor/stages/action_base.h

Lines changed: 6 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -41,23 +41,15 @@
4141
#include <limits>
4242

4343
#include <actionlib/client/simple_action_client.h>
44+
#include <grasping_msgs/GraspPlanningAction.h>
4445

4546
namespace moveit {
4647
namespace task_constructor {
4748
namespace stages {
4849

49-
/**
50-
* @brief Interface allowing stages to use a simple action client
51-
* @param ActionSpec - action message (action message name + "ACTION")
52-
* @details Some stages may require an action client. This class wraps the
53-
* simple client action interface and exposes event based execution callbacks.
54-
*/
55-
template <class ActionSpec>
50+
/** @brief Interface allowing stages to use a simple action client */
5651
class ActionBase
5752
{
58-
protected:
59-
ACTION_DEFINITION(ActionSpec);
60-
6153
public:
6254
/**
6355
* @brief Constructor
@@ -87,39 +79,22 @@ class ActionBase
8779
* @brief Called every time feedback is received for the goal
8880
* @param feedback - pointer to the feedback message
8981
*/
90-
virtual void feedbackCallback(const FeedbackConstPtr& feedback) = 0;
82+
virtual void feedbackCallback(const grasping_msgs::GraspPlanningFeedbackConstPtr& feedback) = 0;
9183

9284
/**
9385
* @brief Called once when the goal completes
9486
* @param state - state info for goal
9587
* @param result - pointer to result message
9688
*/
97-
virtual void doneCallback(const actionlib::SimpleClientGoalState& state, const ResultConstPtr& result) = 0;
89+
virtual void doneCallback(const actionlib::SimpleClientGoalState& state,
90+
const grasping_msgs::GraspPlanningResultConstPtr& result) = 0;
9891

9992
protected:
10093
ros::NodeHandle nh_;
10194
std::string action_name_; // action name space
102-
std::unique_ptr<actionlib::SimpleActionClient<ActionSpec>> clientPtr_; // action client
95+
std::unique_ptr<actionlib::SimpleActionClient<grasping_msgs::GraspPlanningAction>> clientPtr_; // action client
10396
double server_timeout_, goal_timeout_; // connection and goal completed time out
10497
};
105-
106-
template <class ActionSpec>
107-
ActionBase<ActionSpec>::ActionBase(const std::string& action_name, bool spin_thread, double goal_timeout,
108-
double server_timeout)
109-
: action_name_(action_name), server_timeout_(server_timeout), goal_timeout_(goal_timeout) {
110-
clientPtr_.reset(new actionlib::SimpleActionClient<ActionSpec>(nh_, action_name_, spin_thread));
111-
112-
// Negative timeouts are set to zero
113-
server_timeout_ = server_timeout_ < std::numeric_limits<double>::epsilon() ? 0.0 : server_timeout_;
114-
goal_timeout_ = goal_timeout_ < std::numeric_limits<double>::epsilon() ? 0.0 : goal_timeout_;
115-
}
116-
117-
template <class ActionSpec>
118-
ActionBase<ActionSpec>::ActionBase(const std::string& action_name, bool spin_thread)
119-
: action_name_(action_name), server_timeout_(0.0), goal_timeout_(0.0) {
120-
clientPtr_.reset(new actionlib::SimpleActionClient<ActionSpec>(nh_, action_name_, spin_thread));
121-
}
122-
12398
} // namespace stages
12499
} // namespace task_constructor
125100
} // namespace moveit

core/include/moveit/task_constructor/stages/grasp_provider.h

Lines changed: 10 additions & 199 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@
3737
#pragma once
3838

3939
#include <functional>
40+
#include <mutex>
41+
4042
#include <moveit/task_constructor/stages/generate_pose.h>
4143
#include <moveit/task_constructor/stages/action_base.h>
4244
#include <moveit/task_constructor/storage.h>
@@ -48,20 +50,9 @@ namespace moveit {
4850
namespace task_constructor {
4951
namespace stages {
5052

51-
constexpr char LOGNAME[] = "grasp_provider";
52-
53-
/**
54-
* @brief Generate grasp candidates using deep learning approaches
55-
* @param ActionSpec - action message (action message name + "ACTION")
56-
* @details Interfaces with a deep learning based grasp library using a action client
57-
*/
58-
template <class ActionSpec>
59-
class GraspProvider : public GeneratePose, ActionBase<ActionSpec>
53+
/** @brief Generate grasp candidates using deep learning approaches */
54+
class GraspProvider : public GeneratePose, ActionBase
6055
{
61-
private:
62-
typedef ActionBase<ActionSpec> ActionBaseT;
63-
ACTION_DEFINITION(ActionSpec);
64-
6556
public:
6657
/**
6758
* @brief Constructor
@@ -71,7 +62,7 @@ class GraspProvider : public GeneratePose, ActionBase<ActionSpec>
7162
* @param server_timeout - connection to server time out (0 is considered infinite timeout)
7263
* @details Initialize the client and connect to server
7364
*/
74-
GraspProvider(const std::string& action_name, const std::string& stage_name = "generate grasp pose",
65+
GraspProvider(const std::string& action_name, const std::string& stage_name = "grasp provider",
7566
double goal_timeout = 0.0, double server_timeout = 0.0);
7667

7768
/**
@@ -88,8 +79,9 @@ class GraspProvider : public GeneratePose, ActionBase<ActionSpec>
8879
bool monitorGoal();
8980

9081
void activeCallback() override;
91-
void feedbackCallback(const FeedbackConstPtr& feedback) override;
92-
void doneCallback(const actionlib::SimpleClientGoalState& state, const ResultConstPtr& result) override;
82+
void feedbackCallback(const grasping_msgs::GraspPlanningFeedbackConstPtr& feedback) override;
83+
void doneCallback(const actionlib::SimpleClientGoalState& state,
84+
const grasping_msgs::GraspPlanningResultConstPtr& result) override;
9385

9486
void init(const core::RobotModelConstPtr& robot_model) override;
9587
void compute() override;
@@ -106,191 +98,10 @@ class GraspProvider : public GeneratePose, ActionBase<ActionSpec>
10698
void onNewSolution(const SolutionBase& s) override;
10799

108100
private:
101+
std::mutex grasp_mutex_;
109102
bool found_candidates_;
110-
std::vector<geometry_msgs::PoseStamped> grasp_candidates_;
111-
std::vector<double> costs_;
103+
std::vector<moveit_msgs::Grasp> grasp_candidates_;
112104
};
113-
114-
template <class ActionSpec>
115-
GraspProvider<ActionSpec>::GraspProvider(const std::string& action_name, const std::string& stage_name,
116-
double goal_timeout, double server_timeout)
117-
: GeneratePose(stage_name), ActionBaseT(action_name, false, goal_timeout, server_timeout), found_candidates_(false) {
118-
auto& p = properties();
119-
p.declare<std::string>("eef", "name of end-effector");
120-
p.declare<std::string>("object");
121-
p.declare<boost::any>("pregrasp", "pregrasp posture");
122-
p.declare<boost::any>("grasp", "grasp posture");
123-
124-
ROS_INFO_NAMED(LOGNAME, "Waiting for connection to grasp generation action server...");
125-
ActionBaseT::clientPtr_->waitForServer(ros::Duration(ActionBaseT::server_timeout_));
126-
ROS_INFO_NAMED(LOGNAME, "Connected to server");
127-
}
128-
129-
template <class ActionSpec>
130-
void GraspProvider<ActionSpec>::composeGoal() {
131-
Goal goal;
132-
goal.action_name = ActionBaseT::action_name_;
133-
ActionBaseT::clientPtr_->sendGoal(
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));
137-
138-
ROS_INFO_NAMED(LOGNAME, "Goal sent to server: %s", ActionBaseT::action_name_.c_str());
139-
}
140-
141-
template <class ActionSpec>
142-
bool GraspProvider<ActionSpec>::monitorGoal() {
143-
// monitor timeout
144-
const bool monitor_timeout = ActionBaseT::goal_timeout_ > std::numeric_limits<double>::epsilon() ? true : false;
145-
const double timeout_time = ros::Time::now().toSec() + ActionBaseT::goal_timeout_;
146-
147-
while (ActionBaseT::nh_.ok()) {
148-
ros::spinOnce();
149-
150-
// timeout reached
151-
if (ros::Time::now().toSec() > timeout_time && monitor_timeout) {
152-
ActionBaseT::clientPtr_->cancelGoal();
153-
ROS_ERROR_NAMED(LOGNAME, "Grasp pose generator time out reached");
154-
return false;
155-
} else if (found_candidates_) {
156-
// timeout not reached (or not active) and grasps are found
157-
// only way return true
158-
break;
159-
}
160-
}
161-
162-
return true;
163-
}
164-
165-
template <class ActionSpec>
166-
void GraspProvider<ActionSpec>::activeCallback() {
167-
ROS_INFO_NAMED(LOGNAME, "Generate grasp goal now active");
168-
found_candidates_ = false;
169-
}
170-
171-
template <class ActionSpec>
172-
void GraspProvider<ActionSpec>::feedbackCallback(const FeedbackConstPtr& feedback) {
173-
// each candidate should have a cost
174-
if (feedback->grasp_candidates.size() != feedback->costs.size()) {
175-
ROS_ERROR_NAMED(LOGNAME, "Invalid input: each grasp candidate needs an associated cost");
176-
} else {
177-
ROS_INFO_NAMED(LOGNAME, "Grasp generated feedback received %lu candidates: ", feedback->grasp_candidates.size());
178-
179-
grasp_candidates_.resize(feedback->grasp_candidates.size());
180-
costs_.resize(feedback->costs.size());
181-
182-
grasp_candidates_ = feedback->grasp_candidates;
183-
costs_ = feedback->costs;
184-
185-
found_candidates_ = true;
186-
}
187-
}
188-
189-
template <class ActionSpec>
190-
void GraspProvider<ActionSpec>::doneCallback(const actionlib::SimpleClientGoalState& state,
191-
const ResultConstPtr& result) {
192-
if (state == actionlib::SimpleClientGoalState::SUCCEEDED) {
193-
ROS_INFO_NAMED(LOGNAME, "Found grasp candidates (result): %s", result->grasp_state.c_str());
194-
} else {
195-
ROS_ERROR_NAMED(LOGNAME, "No grasp candidates found (state): %s",
196-
ActionBaseT::clientPtr_->getState().toString().c_str());
197-
}
198-
}
199-
200-
template <class ActionSpec>
201-
void GraspProvider<ActionSpec>::init(const core::RobotModelConstPtr& robot_model) {
202-
InitStageException errors;
203-
try {
204-
GeneratePose::init(robot_model);
205-
} catch (InitStageException& e) {
206-
errors.append(e);
207-
}
208-
209-
const auto& props = properties();
210-
211-
// check availability of object
212-
props.get<std::string>("object");
213-
// check availability of eef
214-
const std::string& eef = props.get<std::string>("eef");
215-
if (!robot_model->hasEndEffector(eef)) {
216-
errors.push_back(*this, "unknown end effector: " + eef);
217-
} else {
218-
// check availability of eef pose
219-
const moveit::core::JointModelGroup* jmg = robot_model->getEndEffector(eef);
220-
const std::string& name = props.get<std::string>("pregrasp");
221-
std::map<std::string, double> m;
222-
if (!jmg->getVariableDefaultPositions(name, m)) {
223-
errors.push_back(*this, "unknown end effector pose: " + name);
224-
}
225-
}
226-
227-
if (errors) {
228-
throw errors;
229-
}
230-
}
231-
232-
template <class ActionSpec>
233-
void GraspProvider<ActionSpec>::compute() {
234-
if (upstream_solutions_.empty()) {
235-
return;
236-
}
237-
planning_scene::PlanningScenePtr scene = upstream_solutions_.pop()->end()->scene()->diff();
238-
239-
// set end effector pose
240-
const auto& props = properties();
241-
const std::string& eef = props.get<std::string>("eef");
242-
const moveit::core::JointModelGroup* jmg = scene->getRobotModel()->getEndEffector(eef);
243-
244-
robot_state::RobotState& robot_state = scene->getCurrentStateNonConst();
245-
robot_state.setToDefaultValues(jmg, props.get<std::string>("pregrasp"));
246-
247-
// compose/send goal
248-
composeGoal();
249-
250-
// monitor feedback/results
251-
// blocking function untill timeout reached or results received
252-
if (monitorGoal()) {
253-
// ROS_WARN_NAMED(LOGNAME, "number %lu: ",grasp_candidates_.size());
254-
for (unsigned int i = 0; i < grasp_candidates_.size(); i++) {
255-
InterfaceState state(scene);
256-
state.properties().set("target_pose", grasp_candidates_.at(i));
257-
props.exposeTo(state.properties(), { "pregrasp", "grasp" });
258-
259-
SubTrajectory trajectory;
260-
trajectory.setCost(costs_.at(i));
261-
trajectory.setComment(std::to_string(i));
262-
263-
// add frame at target pose
264-
rviz_marker_tools::appendFrame(trajectory.markers(), grasp_candidates_.at(i), 0.1, "grasp frame");
265-
266-
spawn(std::move(state), std::move(trajectory));
267-
}
268-
}
269-
}
270-
271-
template <class ActionSpec>
272-
void GraspProvider<ActionSpec>::onNewSolution(const SolutionBase& s) {
273-
planning_scene::PlanningSceneConstPtr scene = s.end()->scene();
274-
275-
const auto& props = properties();
276-
const std::string& object = props.get<std::string>("object");
277-
if (!scene->knowsFrameTransform(object)) {
278-
const std::string msg = "object '" + object + "' not in scene";
279-
if (storeFailures()) {
280-
InterfaceState state(scene);
281-
SubTrajectory solution;
282-
solution.markAsFailure();
283-
solution.setComment(msg);
284-
spawn(std::move(state), std::move(solution));
285-
} else {
286-
ROS_WARN_STREAM_NAMED(LOGNAME, msg);
287-
}
288-
return;
289-
}
290-
291-
upstream_solutions_.push(&s);
292-
}
293-
294105
} // namespace stages
295106
} // namespace task_constructor
296107
} // namespace moveit

core/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
<depend>actionlib</depend>
1616
<depend>eigen_conversions</depend>
17+
<depend>grasping_msgs</depend>
1718
<depend>geometry_msgs</depend>
1819
<depend>moveit_core</depend>
1920
<depend>moveit_ros_planning</depend>

core/src/stages/CMakeLists.txt

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

55
${PROJECT_INCLUDE}/stages/action_base.h
66
${PROJECT_INCLUDE}/stages/current_state.h
7-
${PROJECT_INCLUDE}/stages/grasp_provider.h
87
${PROJECT_INCLUDE}/stages/fixed_state.h
98
${PROJECT_INCLUDE}/stages/fixed_cartesian_poses.h
109
${PROJECT_INCLUDE}/stages/generate_pose.h
1110
${PROJECT_INCLUDE}/stages/generate_grasp_pose.h
1211
${PROJECT_INCLUDE}/stages/generate_place_pose.h
12+
${PROJECT_INCLUDE}/stages/grasp_provider.h
1313
${PROJECT_INCLUDE}/stages/compute_ik.h
1414
${PROJECT_INCLUDE}/stages/passthrough.h
1515
${PROJECT_INCLUDE}/stages/predicate_filter.h
@@ -24,12 +24,14 @@ add_library(${PROJECT_NAME}_stages
2424
modify_planning_scene.cpp
2525
fix_collision_objects.cpp
2626

27+
action_base.cpp
2728
current_state.cpp
2829
fixed_state.cpp
2930
fixed_cartesian_poses.cpp
3031
generate_pose.cpp
3132
generate_grasp_pose.cpp
3233
generate_place_pose.cpp
34+
grasp_provider.cpp
3335
compute_ik.cpp
3436
passthrough.cpp
3537
predicate_filter.cpp
@@ -41,6 +43,7 @@ add_library(${PROJECT_NAME}_stages
4143
simple_grasp.cpp
4244
pick.cpp
4345
)
46+
4447
target_link_libraries(${PROJECT_NAME}_stages ${PROJECT_NAME} ${catkin_LIBRARIES})
4548

4649
add_library(${PROJECT_NAME}_stage_plugins

0 commit comments

Comments
 (0)