52 struct OrderGraspQuality
54 OrderGraspQuality(
const std::vector<moveit_msgs::Grasp>& grasps) :
grasps_(grasps)
58 bool operator()(
const std::size_t a,
const std::size_t b)
const
63 const std::vector<moveit_msgs::Grasp>&
grasps_;
69 double timeout = goal.allowed_planning_time;
72 std::string planning_group = goal.group_name;
73 std::string end_effector = goal.end_effector;
74 if (end_effector.empty() && !planning_group.empty())
79 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
85 end_effector = eefs.front();
88 << planning_group <<
"' is ambiguous. Assuming '" << end_effector
92 else if (!end_effector.empty() && planning_group.empty())
97 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
101 if (planning_group.empty())
103 ROS_ERROR_STREAM_NAMED(
"manipulation",
"No parent group to plan in was identified based on end-effector '"
104 << end_effector <<
"'. Please define a parent group in the SRDF.");
105 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
109 ROS_INFO_STREAM_NAMED(
"manipulation",
"Assuming the planning group for end effector '" << end_effector <<
"' is '"
110 << planning_group <<
"'");
113 end_effector.empty() ? nullptr :
planning_scene->getRobotModel()->getEndEffector(end_effector);
116 ROS_ERROR_NAMED(
"manipulation",
"No end-effector specified for pick action");
117 error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
125 ManipulationPlanSharedDataPtr plan_data(
new ManipulationPlanSharedData());
126 ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
127 plan_data->planning_group_ =
planning_scene->getRobotModel()->getJointModelGroup(planning_group);
128 plan_data->end_effector_group_ = eef;
129 plan_data->ik_link_ =
planning_scene->getRobotModel()->getLinkModel(ik_link);
130 plan_data->timeout_ = endtime;
131 plan_data->path_constraints_ = goal.path_constraints;
132 plan_data->planner_id_ = goal.planner_id;
133 plan_data->minimize_object_distance_ = goal.minimize_object_distance;
134 plan_data->max_goal_sampling_attempts_ = 2;
135 moveit_msgs::AttachedCollisionObject& attach_object_msg = plan_data->diff_attached_object_;
138 attach_object_msg.link_name = ik_link;
139 attach_object_msg.object.id = goal.target_name;
140 attach_object_msg.object.operation = moveit_msgs::CollisionObject::ADD;
141 attach_object_msg.touch_links =
142 goal.attached_object_touch_links.empty() ? eef->
getLinkModelNames() : goal.attached_object_touch_links;
143 collision_detection::AllowedCollisionMatrixPtr approach_grasp_acm(
147 approach_grasp_acm->setEntry(goal.target_name, attach_object_msg.touch_links,
true);
149 approach_grasp_acm->setEntry(eef->
getLinkModelNames(), goal.allowed_touch_objects,
true);
150 if (!goal.support_surface_name.empty())
153 approach_grasp_acm->setEntry(goal.support_surface_name, goal.target_name,
true);
156 if (goal.allow_gripper_support_collision)
157 approach_grasp_acm->setEntry(goal.support_surface_name, eef->
getLinkModelNames(),
true);
162 ManipulationStagePtr stage1(
164 ManipulationStagePtr stage2(
new ApproachAndTranslateStage(
planning_scene, approach_grasp_acm));
172 std::vector<std::size_t> grasp_order(goal.possible_grasps.size());
173 for (std::size_t i = 0; i < goal.possible_grasps.size(); ++i)
175 OrderGraspQuality oq(goal.possible_grasps);
177 std::stable_sort(grasp_order.begin(), grasp_order.end(), oq);
180 for (std::size_t i = 0; i < goal.possible_grasps.size(); ++i)
182 ManipulationPlanPtr p(
new ManipulationPlan(const_plan_data));
183 const moveit_msgs::Grasp& g = goal.possible_grasps[grasp_order[i]];
184 p->approach_ = g.pre_grasp_approach;
185 p->retreat_ = g.post_grasp_retreat;
186 p->goal_pose_ = g.grasp_pose;
187 p->id_ = grasp_order[i];
189 if (p->goal_pose_.header.frame_id.empty())
190 p->goal_pose_.header.frame_id = goal.target_name;
191 p->approach_posture_ = g.pre_grasp_posture;
192 p->retreat_posture_ = g.grasp_posture;
203 error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
207 error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
210 error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
211 if (!goal.possible_grasps.empty())
213 ROS_WARN_NAMED(
"manipulation",
"All supplied grasps failed. Retrying last grasp in verbose mode.");
225 ROS_INFO_NAMED(
"manipulation",
"Pickup planning completed after %lf seconds", last_plan_time_);
227 return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
230 PickPlanPtr PickPlace::planPick(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
231 const moveit_msgs::PickupGoal& goal)
const
233 PickPlanPtr p(
new PickPlan(shared_from_this()));
238 p->plan(
planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
240 if (display_computed_motion_plans_)
242 const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
243 if (!success.empty())
244 visualizePlan(success.back());
249 const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
250 visualizeGrasps(success);
251 const std::vector<pick_place::ManipulationPlanPtr>& failed = p->getFailedManipulationPlans();
252 visualizeGrasps(failed);