54 struct OrderPlaceLocationQuality
56 OrderPlaceLocationQuality(
const std::vector<moveit_msgs::PlaceLocation>& places) :
places_(places)
60 bool operator()(
const std::size_t a,
const std::size_t b)
const
65 const std::vector<moveit_msgs::PlaceLocation>&
places_;
68 bool transformToEndEffectorGoal(
const geometry_msgs::PoseStamped& goal_pose,
72 if (fixed_transforms.empty())
75 Eigen::Isometry3d end_effector_transform;
77 end_effector_transform = end_effector_transform * fixed_transforms[0].inverse();
78 place_pose.header = goal_pose.header;
79 place_pose.pose =
tf2::toMsg(end_effector_transform);
84 bool PlacePlan::plan(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
const moveit_msgs::PlaceGoal& goal)
86 double timeout = goal.allowed_planning_time;
88 std::string attached_object_name = goal.attached_object_name;
93 if (
planning_scene->getRobotModel()->hasEndEffector(goal.group_name))
95 eef =
planning_scene->getRobotModel()->getEndEffector(goal.group_name);
99 if (eef_parent.empty())
101 ROS_ERROR_STREAM_NAMED(
"manipulation",
"No parent group to plan in was identified based on end-effector '"
103 <<
"'. Please define a parent group in the SRDF.");
104 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
108 jmg =
planning_scene->getRobotModel()->getJointModelGroup(eef_parent);
114 jmg = goal.group_name.empty() ? nullptr :
planning_scene->getRobotModel()->getJointModelGroup(goal.group_name);
119 if (eef_names.empty())
122 "There are no end-effectors specified for group '" << goal.group_name <<
"'");
123 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
128 for (
const std::string& eef_name : eef_names)
130 std::vector<const moveit::core::AttachedBody*> attached_bodies;
135 planning_scene->getCurrentState().getAttachedBodies(attached_bodies, eg);
141 if (attached_link_model)
143 std::vector<const moveit::core::AttachedBody*> attached_bodies2;
144 planning_scene->getCurrentState().getAttachedBodies(attached_bodies2, attached_link_model);
145 attached_bodies.insert(attached_bodies.end(), attached_bodies2.begin(), attached_bodies2.end());
150 if (!attached_bodies.empty())
154 if (!attached_object_name.empty())
158 if (attached_body->
getName() == attached_object_name)
174 <<
"' that are currently holding objects. It is ambiguous "
175 "which end-effector to use. Please specify it explicitly.");
176 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
187 if (!attached_object_name.empty() && !eef)
190 planning_scene->getCurrentState().getAttachedBody(attached_object_name);
196 const std::vector<const moveit::core::JointModelGroup*>& eefs =
199 if (end_effector->hasLinkModel(link->
getName()))
204 << link->
getName() <<
"' which is where the body '"
205 << attached_object_name
206 <<
"' is attached. It is unclear which end-effector to use.");
207 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
217 if (eef_parent.empty())
219 ROS_ERROR_STREAM_NAMED(
"manipulation",
"No parent group to plan in was identified based on end-effector '"
221 <<
"'. Please define a parent group in the SRDF.");
222 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
226 jmg =
planning_scene->getRobotModel()->getJointModelGroup(eef_parent);
232 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
238 while (attached_object_name.empty() && loop_count < 2)
242 std::vector<const moveit::core::AttachedBody*> attached_bodies;
243 planning_scene->getCurrentState().getAttachedBodies(attached_bodies, loop_count == 0 ? eef : jmg);
246 if (attached_bodies.size() > 1)
249 "Multiple attached bodies for group '%s' but no explicit attached object to place was specified",
250 goal.group_name.c_str());
251 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
255 attached_object_name = attached_bodies[0]->getName();
259 planning_scene->getCurrentState().getAttachedBody(attached_object_name);
262 ROS_ERROR_NAMED(
"manipulation",
"There is no object to detach for place action");
263 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
270 ManipulationPlanSharedDataPtr plan_data(
new ManipulationPlanSharedData());
271 ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
272 plan_data->planning_group_ = jmg;
273 plan_data->end_effector_group_ = eef;
276 plan_data->timeout_ = endtime;
277 plan_data->path_constraints_ = goal.path_constraints;
278 plan_data->planner_id_ = goal.planner_id;
279 plan_data->minimize_object_distance_ =
false;
280 plan_data->max_goal_sampling_attempts_ = 2;
281 moveit_msgs::AttachedCollisionObject& detach_object_msg = plan_data->diff_attached_object_;
285 detach_object_msg.object.id = attached_object_name;
286 detach_object_msg.object.operation = moveit_msgs::CollisionObject::REMOVE;
288 collision_detection::AllowedCollisionMatrixPtr approach_place_acm(
292 approach_place_acm->setEntry(eef->
getLinkModelNames(), goal.allowed_touch_objects,
true);
296 approach_place_acm->setEntry(attached_object_name, touch_links,
true);
298 if (!goal.support_surface_name.empty())
301 approach_place_acm->setEntry(goal.support_surface_name, attached_object_name,
true);
304 if (goal.allow_gripper_support_collision)
305 approach_place_acm->setEntry(goal.support_surface_name, eef->
getLinkModelNames(),
true);
311 ManipulationStagePtr stage1(
312 new ReachableAndValidPoseFilter(
planning_scene, approach_place_acm, pick_place_->getConstraintsSamplerManager()));
313 ManipulationStagePtr stage2(
new ApproachAndTranslateStage(
planning_scene, approach_place_acm));
314 ManipulationStagePtr stage3(
new PlanStage(
planning_scene, pick_place_->getPlanningPipeline()));
315 pipeline_.addStage(stage1).addStage(stage2).addStage(stage3);
322 std::vector<std::size_t> place_locations_order(goal.place_locations.size());
323 for (std::size_t i = 0; i < goal.place_locations.size(); ++i)
324 place_locations_order[i] = i;
325 OrderPlaceLocationQuality oq(goal.place_locations);
327 std::stable_sort(place_locations_order.begin(), place_locations_order.end(), oq);
330 for (std::size_t i = 0; i < goal.place_locations.size(); ++i)
332 ManipulationPlanPtr p(
new ManipulationPlan(const_plan_data));
333 const moveit_msgs::PlaceLocation& pl = goal.place_locations[place_locations_order[i]];
336 p->goal_pose_ = pl.place_pose;
340 if (!transformToEndEffectorGoal(pl.place_pose, attached_body, p->goal_pose_))
342 p->goal_pose_ = pl.place_pose;
343 ROS_ERROR_NAMED(
"manipulation",
"Unable to transform the desired pose of the object to the pose of the "
347 p->approach_ = pl.pre_place_approach;
348 p->retreat_ = pl.post_place_retreat;
349 p->retreat_posture_ = pl.post_place_posture;
350 p->id_ = place_locations_order[i];
351 if (p->retreat_posture_.joint_names.empty())
355 ROS_INFO_NAMED(
"manipulation",
"Added %d place locations", (
int)goal.place_locations.size());
358 waitForPipeline(endtime);
364 if (!getSuccessfulManipulationPlans().empty())
365 error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
368 if (last_plan_time_ > timeout)
369 error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
372 error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
373 if (!goal.place_locations.empty())
375 ROS_WARN_NAMED(
"manipulation",
"All supplied place locations failed. Retrying last location in verbose mode.");
378 pipeline_.setVerbose(
true);
380 pipeline_.reprocessLastFailure();
383 pipeline_.setVerbose(
false);
387 ROS_INFO_NAMED(
"manipulation",
"Place planning completed after %lf seconds", last_plan_time_);
389 return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
392 PlacePlanPtr PickPlace::planPlace(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
393 const moveit_msgs::PlaceGoal& goal)
const
395 PlacePlanPtr p(
new PlacePlan(shared_from_this()));
399 p->plan(
planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
401 if (display_computed_motion_plans_)
403 const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
404 if (!success.empty())
405 visualizePlan(success.back());
410 const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
411 visualizeGrasps(success);
412 const std::vector<pick_place::ManipulationPlanPtr>& failed = p->getFailedManipulationPlans();
413 visualizeGrasps(failed);