42 constexpr
char LOGNAME[] =
"moveit_task_constructor_demo";
46 if (!
psi.applyCollisionObject(
object))
47 throw std::runtime_error(
"Failed to spawn object: " +
object.
id);
51 std::string table_name, table_reference_frame;
52 std::vector<double> table_dimensions;
53 geometry_msgs::Pose
pose;
54 std::size_t errors = 0;
61 moveit_msgs::CollisionObject
object;
62 object.id = table_name;
63 object.header.frame_id = table_reference_frame;
64 object.primitives.resize(1);
65 object.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
66 object.primitives[0].dimensions = table_dimensions;
67 pose.position.z -= 0.5 * table_dimensions[2];
68 object.primitive_poses.push_back(
pose);
74 std::vector<double> object_dimensions;
76 std::size_t
error = 0;
83 moveit_msgs::CollisionObject
object;
85 object.header.frame_id = object_reference_frame;
86 object.primitives.resize(1);
87 object.primitives[0].type = shape_msgs::SolidPrimitive::CYLINDER;
88 object.primitives[0].dimensions = object_dimensions;
89 pose.position.z += 0.5 * object_dimensions[0];
90 object.primitive_poses.push_back(
pose);
98 if (pnh.
param(
"spawn_table",
true))
104 : pnh_(pnh), task_name_(task_name) {
108 void PickPlaceTask::loadParameters() {
135 support_surfaces_ = { surface_link_ };
148 bool PickPlaceTask::init() {
150 const std::string
object = object_name_;
159 t.stages()->setName(task_name_);
165 auto sampling_planner = std::make_shared<solvers::PipelinePlanner>();
166 sampling_planner->setProperty(
"goal_joint_tolerance", 1e-5);
169 auto cartesian_planner = std::make_shared<solvers::CartesianPath>();
170 cartesian_planner->setMaxVelocityScalingFactor(1.0);
171 cartesian_planner->setMaxAccelerationScalingFactor(1.0);
172 cartesian_planner->setStepSize(.01);
175 t.setProperty(
"group", arm_group_name_);
176 t.setProperty(
"eef", eef_name_);
177 t.setProperty(
"hand", hand_group_name_);
178 t.setProperty(
"hand_grasping_frame", hand_frame_);
179 t.setProperty(
"ik_frame", hand_frame_);
187 auto current_state = std::make_unique<stages::CurrentState>(
"current state");
190 auto applicability_filter =
192 applicability_filter->setPredicate([
object](
const SolutionBase&
s, std::string& comment) {
193 if (
s.start()->scene()->getCurrentState().hasAttachedBody(
object)) {
194 comment =
"object with id '" + object +
"' is already attached and cannot be picked";
207 Stage* initial_state_ptr =
nullptr;
209 auto stage = std::make_unique<stages::MoveTo>(
"open hand", sampling_planner);
210 stage->setGroup(hand_group_name_);
211 stage->setGoal(hand_open_pose_);
212 initial_state_ptr =
stage.get();
223 stages::Connect::GroupPlannerVector
planners = { { arm_group_name_, sampling_planner },
224 { hand_group_name_, sampling_planner } };
225 auto stage = std::make_unique<stages::Connect>(
"move to pick",
planners);
226 stage->setTimeout(5.0);
227 stage->properties().configureInitFrom(Stage::PARENT);
236 Stage* pick_stage_ptr =
nullptr;
239 auto grasp = std::make_unique<SerialContainer>(
"pick object");
240 t.properties().exposeTo(
grasp->properties(), {
"eef",
"hand",
"group",
"ik_frame" });
241 grasp->properties().configureInitFrom(Stage::PARENT, {
"eef",
"hand",
"group",
"ik_frame" });
248 auto stage = std::make_unique<stages::MoveRelative>(
"approach object", cartesian_planner);
249 stage->properties().set(
"marker_ns",
"approach_object");
250 stage->properties().set(
"link", hand_frame_);
251 stage->properties().configureInitFrom(Stage::PARENT, {
"group" });
252 stage->setMinMaxDistance(approach_object_min_dist_, approach_object_max_dist_);
255 geometry_msgs::Vector3Stamped
vec;
256 vec.header.frame_id = hand_frame_;
258 stage->setDirection(vec);
267 auto stage = std::make_unique<stages::GenerateGraspPose>(
"generate grasp pose");
268 stage->properties().configureInitFrom(Stage::PARENT);
269 stage->properties().set(
"marker_ns",
"grasp_pose");
270 stage->setPreGraspPose(hand_open_pose_);
271 stage->setObject(
object);
272 stage->setAngleDelta(M_PI / 12);
273 stage->setMonitoredStage(initial_state_ptr);
276 auto wrapper = std::make_unique<stages::ComputeIK>(
"grasp pose IK",
std::move(
stage));
277 wrapper->setMaxIKSolutions(8);
278 wrapper->setMinSolutionDistance(1.0);
279 wrapper->setIKFrame(grasp_frame_transform_, hand_frame_);
280 wrapper->properties().configureInitFrom(Stage::PARENT, {
"eef",
"group" });
281 wrapper->properties().configureInitFrom(Stage::INTERFACE,
291 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"allow collision (hand,object)");
292 stage->allowCollisions(
293 object,
t.getRobotModel()->getJointModelGroup(hand_group_name_)->getLinkModelNamesWithCollisionGeometry(),
302 auto stage = std::make_unique<stages::MoveTo>(
"close hand", sampling_planner);
303 stage->setGroup(hand_group_name_);
304 stage->setGoal(hand_close_pose_);
312 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"attach object");
313 stage->attachObject(
object, hand_frame_);
321 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"allow collision (object,support)");
322 stage->allowCollisions({
object }, support_surfaces_,
true);
330 auto stage = std::make_unique<stages::MoveRelative>(
"lift object", cartesian_planner);
331 stage->properties().configureInitFrom(Stage::PARENT, {
"group" });
332 stage->setMinMaxDistance(lift_object_min_dist_, lift_object_max_dist_);
333 stage->setIKFrame(hand_frame_);
334 stage->properties().set(
"marker_ns",
"lift_object");
337 geometry_msgs::Vector3Stamped
vec;
338 vec.header.frame_id = world_frame_;
340 stage->setDirection(vec);
348 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"forbid collision (object,support)");
349 stage->allowCollisions({
object }, support_surfaces_,
false);
353 pick_stage_ptr =
grasp.get();
366 auto stage = std::make_unique<stages::Connect>(
367 "move to place", stages::Connect::GroupPlannerVector{ { arm_group_name_, sampling_planner } });
368 stage->setTimeout(5.0);
369 stage->properties().configureInitFrom(Stage::PARENT);
380 auto place = std::make_unique<SerialContainer>(
"place object");
381 t.properties().exposeTo(
place->properties(), {
"eef",
"hand",
"group" });
382 place->properties().configureInitFrom(Stage::PARENT, {
"eef",
"hand",
"group" });
388 auto stage = std::make_unique<stages::MoveRelative>(
"lower object", cartesian_planner);
389 stage->properties().set(
"marker_ns",
"lower_object");
390 stage->properties().set(
"link", hand_frame_);
391 stage->properties().configureInitFrom(Stage::PARENT, {
"group" });
392 stage->setMinMaxDistance(.03, .13);
395 geometry_msgs::Vector3Stamped
vec;
396 vec.header.frame_id = world_frame_;
398 stage->setDirection(vec);
407 auto stage = std::make_unique<stages::GeneratePlacePose>(
"generate place pose");
408 stage->properties().configureInitFrom(Stage::PARENT, {
"ik_frame" });
409 stage->properties().set(
"marker_ns",
"place_pose");
410 stage->setObject(
object);
413 geometry_msgs::PoseStamped
p;
414 p.header.frame_id = object_reference_frame_;
415 p.pose = place_pose_;
416 p.pose.position.z += 0.5 * object_dimensions_[0] + place_surface_offset_;
418 stage->setMonitoredStage(pick_stage_ptr);
421 auto wrapper = std::make_unique<stages::ComputeIK>(
"place pose IK",
std::move(
stage));
422 wrapper->setMaxIKSolutions(2);
423 wrapper->setIKFrame(grasp_frame_transform_, hand_frame_);
424 wrapper->properties().configureInitFrom(Stage::PARENT, {
"eef",
"group" });
425 wrapper->properties().configureInitFrom(Stage::INTERFACE, {
"target_pose" });
433 auto stage = std::make_unique<stages::MoveTo>(
"open hand", sampling_planner);
434 stage->setGroup(hand_group_name_);
435 stage->setGoal(hand_open_pose_);
443 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"forbid collision (hand,object)");
444 stage->allowCollisions(object_name_, *
t.getRobotModel()->getJointModelGroup(hand_group_name_),
false);
452 auto stage = std::make_unique<stages::ModifyPlanningScene>(
"detach object");
453 stage->detachObject(object_name_, hand_frame_);
461 auto stage = std::make_unique<stages::MoveRelative>(
"retreat after place", cartesian_planner);
462 stage->properties().configureInitFrom(Stage::PARENT, {
"group" });
463 stage->setMinMaxDistance(.12, .25);
464 stage->setIKFrame(hand_frame_);
465 stage->properties().set(
"marker_ns",
"retreat");
466 geometry_msgs::Vector3Stamped
vec;
467 vec.header.frame_id = hand_frame_;
469 stage->setDirection(vec);
483 auto stage = std::make_unique<stages::MoveTo>(
"move home", sampling_planner);
484 stage->properties().configureInitFrom(Stage::PARENT, {
"group" });
485 stage->setGoal(arm_home_pose_);
486 stage->restrictDirection(stages::MoveTo::FORWARD);
493 }
catch (InitStageException& e) {
501 bool PickPlaceTask::plan() {
503 int max_solutions = pnh_.param<
int>(
"max_solutions", 10);
505 return static_cast<bool>(task_->plan(max_solutions));
508 bool PickPlaceTask::execute() {
510 moveit_msgs::MoveItErrorCodes execute_result;
512 execute_result = task_->execute(*task_->solutions().front());
514 if (execute_result.val != moveit_msgs::MoveItErrorCodes::SUCCESS) {