pick_place_action_capability.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
41 
43  : MoveGroupCapability("PickPlaceAction"), pickup_state_(IDLE)
44 {
45 }
46 
48 {
49  pick_place_ = std::make_shared<pick_place::PickPlace>(context_->planning_pipeline_);
50  pick_place_->displayComputedMotionPlans(true);
51 
52  if (context_->debug_)
53  pick_place_->displayProcessedGrasps(true);
54 
55  // start the pickup action server
56  pickup_action_server_ = std::make_unique<actionlib::SimpleActionServer<moveit_msgs::PickupAction>>(
57  root_node_handle_, PICKUP_ACTION, [this](const auto& goal) { executePickupCallback(goal); }, false);
58  pickup_action_server_->registerPreemptCallback([this] { preemptPickupCallback(); });
59  pickup_action_server_->start();
60 
61  // start the place action server
62  place_action_server_ = std::make_unique<actionlib::SimpleActionServer<moveit_msgs::PlaceAction>>(
63  root_node_handle_, PLACE_ACTION, [this](const auto& goal) { executePlaceCallback(goal); }, false);
64  place_action_server_->registerPreemptCallback([this] { preemptPlaceCallback(); });
65  place_action_server_->start();
66 }
67 
69 {
70  setPickupState(MONITOR);
71 }
72 
74 {
75  setPickupState(LOOK);
76 }
77 
79 {
80  setPlaceState(MONITOR);
81 }
82 
84 {
85  setPlaceState(LOOK);
86 }
87 
88 void move_group::MoveGroupPickPlaceAction::executePickupCallbackPlanOnly(const moveit_msgs::PickupGoalConstPtr& goal,
89  moveit_msgs::PickupResult& action_res)
90 {
91  pick_place::PickPlanPtr plan;
92  try
93  {
94  planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
95  plan = pick_place_->planPick(ps, *goal);
96  }
97  catch (std::exception& ex)
98  {
99  ROS_ERROR_NAMED("manipulation", "Pick&place threw an exception: %s", ex.what());
100  }
101 
102  if (plan)
103  {
104  const std::vector<pick_place::ManipulationPlanPtr>& success = plan->getSuccessfulManipulationPlans();
105  if (success.empty())
106  {
107  action_res.error_code = plan->getErrorCode();
108  }
109  else
110  {
111  const pick_place::ManipulationPlanPtr& result = success.back();
112  convertToMsg(result->trajectories_, action_res.trajectory_start, action_res.trajectory_stages);
113  action_res.trajectory_descriptions.resize(result->trajectories_.size());
114  for (std::size_t i = 0; i < result->trajectories_.size(); ++i)
115  action_res.trajectory_descriptions[i] = result->trajectories_[i].description_;
116  if (result->id_ < goal->possible_grasps.size())
117  action_res.grasp = goal->possible_grasps[result->id_];
118  action_res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
119  action_res.planning_time = plan->getLastPlanTime();
120  }
121  }
122  else
123  {
124  action_res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
125  }
126 }
127 
128 void move_group::MoveGroupPickPlaceAction::executePlaceCallbackPlanOnly(const moveit_msgs::PlaceGoalConstPtr& goal,
129  moveit_msgs::PlaceResult& action_res)
130 {
131  pick_place::PlacePlanPtr plan;
132  try
133  {
134  planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
135  plan = pick_place_->planPlace(ps, *goal);
136  }
137  catch (std::exception& ex)
138  {
139  ROS_ERROR_NAMED("manipulation", "Pick&place threw an exception: %s", ex.what());
140  }
141 
142  if (plan)
143  {
144  const std::vector<pick_place::ManipulationPlanPtr>& success = plan->getSuccessfulManipulationPlans();
145  if (success.empty())
146  {
147  action_res.error_code = plan->getErrorCode();
148  }
149  else
150  {
151  const pick_place::ManipulationPlanPtr& result = success.back();
152  convertToMsg(result->trajectories_, action_res.trajectory_start, action_res.trajectory_stages);
153  action_res.trajectory_descriptions.resize(result->trajectories_.size());
154  for (std::size_t i = 0; i < result->trajectories_.size(); ++i)
155  action_res.trajectory_descriptions[i] = result->trajectories_[i].description_;
156  if (result->id_ < goal->place_locations.size())
157  action_res.place_location = goal->place_locations[result->id_];
158  action_res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
159  action_res.planning_time = plan->getLastPlanTime();
160  }
161  }
162  else
163  {
164  action_res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
165  }
166 }
167 
168 bool move_group::MoveGroupPickPlaceAction::planUsingPickPlacePickup(const moveit_msgs::PickupGoal& goal,
169  moveit_msgs::PickupResult* action_res,
171 {
172  setPickupState(PLANNING);
173 
175 
176  pick_place::PickPlanPtr pick_plan;
177  try
178  {
179  pick_plan = pick_place_->planPick(plan.planning_scene_, goal);
180  }
181  catch (std::exception& ex)
182  {
183  ROS_ERROR_NAMED("manipulation", "Pick&place threw an exception: %s", ex.what());
184  }
185 
186  if (pick_plan)
187  {
188  const std::vector<pick_place::ManipulationPlanPtr>& success = pick_plan->getSuccessfulManipulationPlans();
189  if (success.empty())
190  {
191  plan.error_code_ = pick_plan->getErrorCode();
192  }
193  else
194  {
195  const pick_place::ManipulationPlanPtr& result = success.back();
196  plan.plan_components_ = result->trajectories_;
197  if (result->id_ < goal.possible_grasps.size())
198  action_res->grasp = goal.possible_grasps[result->id_];
199  plan.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
200  action_res->planning_time = pick_plan->getLastPlanTime();
201  }
202  }
203  else
204  {
205  plan.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
206  }
207 
208  return plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
209 }
210 
212  moveit_msgs::PlaceResult* action_res,
214 {
215  setPlaceState(PLANNING);
216 
218 
219  pick_place::PlacePlanPtr place_plan;
220  try
221  {
222  place_plan = pick_place_->planPlace(plan.planning_scene_, goal);
223  }
224  catch (std::exception& ex)
225  {
226  ROS_ERROR_NAMED("manipulation", "Pick&place threw an exception: %s", ex.what());
227  }
228 
229  if (place_plan)
230  {
231  const std::vector<pick_place::ManipulationPlanPtr>& success = place_plan->getSuccessfulManipulationPlans();
232  if (success.empty())
233  {
234  plan.error_code_ = place_plan->getErrorCode();
235  }
236  else
237  {
238  const pick_place::ManipulationPlanPtr& result = success.back();
239  plan.plan_components_ = result->trajectories_;
240  if (result->id_ < goal.place_locations.size())
241  action_res->place_location = goal.place_locations[result->id_];
242  plan.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
243  action_res->planning_time = place_plan->getLastPlanTime();
244  }
245  }
246  else
247  {
248  plan.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
249  }
250 
251  return plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
252 }
253 
255  const moveit_msgs::PickupGoalConstPtr& goal, moveit_msgs::PickupResult& action_res)
256 {
258 
259  opt.replan_ = goal->planning_options.replan;
260  opt.replan_attempts_ = goal->planning_options.replan_attempts;
261  opt.replan_delay_ = goal->planning_options.replan_delay;
262  opt.before_execution_callback_ = [this] { startPickupExecutionCallback(); };
263 
264  opt.plan_callback_ = [this, &g = *goal, result_ptr = &action_res](plan_execution::ExecutableMotionPlan& plan) {
265  return planUsingPickPlacePickup(g, result_ptr, plan);
266  };
267  if (goal->planning_options.look_around && context_->plan_with_sensing_)
268  {
269  opt.plan_callback_ = [plan_with_sensing = context_->plan_with_sensing_.get(), planner = opt.plan_callback_,
270  attempts = goal->planning_options.look_around_attempts,
271  safe_execution_cost = goal->planning_options.max_safe_execution_cost](
273  return plan_with_sensing->computePlan(plan, planner, attempts, safe_execution_cost);
274  };
275  context_->plan_with_sensing_->setBeforeLookCallback([this] { startPickupLookCallback(); });
276  }
277 
279  context_->plan_execution_->planAndExecute(plan, goal->planning_options.planning_scene_diff, opt);
280 
281  convertToMsg(plan.plan_components_, action_res.trajectory_start, action_res.trajectory_stages);
282  action_res.trajectory_descriptions.resize(plan.plan_components_.size());
283  for (std::size_t i = 0; i < plan.plan_components_.size(); ++i)
284  action_res.trajectory_descriptions[i] = plan.plan_components_[i].description_;
285  action_res.error_code = plan.error_code_;
286 }
287 
288 void move_group::MoveGroupPickPlaceAction::executePlaceCallbackPlanAndExecute(const moveit_msgs::PlaceGoalConstPtr& goal,
289  moveit_msgs::PlaceResult& action_res)
290 {
292 
293  opt.replan_ = goal->planning_options.replan;
294  opt.replan_attempts_ = goal->planning_options.replan_attempts;
295  opt.replan_delay_ = goal->planning_options.replan_delay;
296  opt.before_execution_callback_ = [this] { startPlaceExecutionCallback(); };
297  opt.plan_callback_ = [this, g = *goal, result_ptr = &action_res](plan_execution::ExecutableMotionPlan& plan) {
298  return planUsingPickPlacePlace(g, result_ptr, plan);
299  };
300  if (goal->planning_options.look_around && context_->plan_with_sensing_)
301  {
302  opt.plan_callback_ = [plan_with_sensing = context_->plan_with_sensing_.get(), planner = opt.plan_callback_,
303  attempts = goal->planning_options.look_around_attempts,
304  safe_execution_cost = goal->planning_options.max_safe_execution_cost](
306  return plan_with_sensing->computePlan(plan, planner, attempts, safe_execution_cost);
307  };
308  context_->plan_with_sensing_->setBeforeLookCallback([this] { startPlaceLookCallback(); });
309  }
310 
312  context_->plan_execution_->planAndExecute(plan, goal->planning_options.planning_scene_diff, opt);
313 
314  convertToMsg(plan.plan_components_, action_res.trajectory_start, action_res.trajectory_stages);
315  action_res.trajectory_descriptions.resize(plan.plan_components_.size());
316  for (std::size_t i = 0; i < plan.plan_components_.size(); ++i)
317  action_res.trajectory_descriptions[i] = plan.plan_components_[i].description_;
318  action_res.error_code = plan.error_code_;
319 }
320 
321 void move_group::MoveGroupPickPlaceAction::executePickupCallback(const moveit_msgs::PickupGoalConstPtr& input_goal)
322 {
323  setPickupState(PLANNING);
324 
325  // before we start planning, ensure that we have the latest robot state received...
326  context_->planning_scene_monitor_->waitForCurrentRobotState(ros::Time::now());
327  context_->planning_scene_monitor_->updateFrameTransforms();
328 
329  moveit_msgs::PickupGoalConstPtr goal;
330  if (input_goal->possible_grasps.empty())
331  {
332  moveit_msgs::PickupGoal* copy(new moveit_msgs::PickupGoal(*input_goal));
333  goal.reset(copy);
334  fillGrasps(*copy);
335  }
336  else
337  goal = input_goal;
338 
339  moveit_msgs::PickupResult action_res;
340 
341  if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
342  {
343  if (!goal->planning_options.plan_only)
344  ROS_WARN_NAMED("manipulation", "This instance of MoveGroup is not allowed to execute trajectories but the pick "
345  "goal request has plan_only set to false. Only a motion plan will be computed "
346  "anyway.");
347  executePickupCallbackPlanOnly(goal, action_res);
348  }
349  else
350  executePickupCallbackPlanAndExecute(goal, action_res);
351 
352  bool planned_trajectory_empty = action_res.trajectory_stages.empty();
353  std::string response =
354  getActionResultString(action_res.error_code, planned_trajectory_empty, goal->planning_options.plan_only);
355  if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
356  pickup_action_server_->setSucceeded(action_res, response);
357  else
358  {
359  if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
360  pickup_action_server_->setPreempted(action_res, response);
361  else
362  pickup_action_server_->setAborted(action_res, response);
363  }
364 
365  setPickupState(IDLE);
366 }
367 
368 void move_group::MoveGroupPickPlaceAction::executePlaceCallback(const moveit_msgs::PlaceGoalConstPtr& goal)
369 {
370  setPlaceState(PLANNING);
371 
372  // before we start planning, ensure that we have the latest robot state received...
373  context_->planning_scene_monitor_->waitForCurrentRobotState(ros::Time::now());
374  context_->planning_scene_monitor_->updateFrameTransforms();
375 
376  moveit_msgs::PlaceResult action_res;
377 
378  if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
379  {
380  if (!goal->planning_options.plan_only)
381  ROS_WARN_NAMED("manipulation", "This instance of MoveGroup is not allowed to execute trajectories but the place "
382  "goal request has plan_only set to false. Only a motion plan will be computed "
383  "anyway.");
384  executePlaceCallbackPlanOnly(goal, action_res);
385  }
386  else
387  executePlaceCallbackPlanAndExecute(goal, action_res);
388 
389  bool planned_trajectory_empty = action_res.trajectory_stages.empty();
390  std::string response =
391  getActionResultString(action_res.error_code, planned_trajectory_empty, goal->planning_options.plan_only);
392  if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
393  place_action_server_->setSucceeded(action_res, response);
394  else
395  {
396  if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
397  place_action_server_->setPreempted(action_res, response);
398  else
399  place_action_server_->setAborted(action_res, response);
400  }
401 
402  setPlaceState(IDLE);
403 }
404 
406 {
407 }
408 
410 {
411 }
412 
414 {
415  pickup_state_ = state;
416  pickup_feedback_.state = stateToStr(state);
417  pickup_action_server_->publishFeedback(pickup_feedback_);
418 }
419 
421 {
422  place_state_ = state;
423  place_feedback_.state = stateToStr(state);
424  place_action_server_->publishFeedback(place_feedback_);
425 }
426 
427 void move_group::MoveGroupPickPlaceAction::fillGrasps(moveit_msgs::PickupGoal& goal)
428 {
429  planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
430 
431  ROS_DEBUG_NAMED("manipulation", "Using default grasp poses");
432  goal.minimize_object_distance = true;
433 
434  // add a number of default grasp points
435  // \todo add more!
436  moveit_msgs::Grasp g;
437  g.grasp_pose.header.frame_id = goal.target_name;
438  g.grasp_pose.pose.position.x = -0.2;
439  g.grasp_pose.pose.position.y = 0.0;
440  g.grasp_pose.pose.position.z = 0.0;
441  g.grasp_pose.pose.orientation.x = 0.0;
442  g.grasp_pose.pose.orientation.y = 0.0;
443  g.grasp_pose.pose.orientation.z = 0.0;
444  g.grasp_pose.pose.orientation.w = 1.0;
445 
446  g.pre_grasp_approach.direction.header.frame_id = lscene->getPlanningFrame();
447  g.pre_grasp_approach.direction.vector.x = 1.0;
448  g.pre_grasp_approach.min_distance = 0.1;
449  g.pre_grasp_approach.desired_distance = 0.2;
450 
451  g.post_grasp_retreat.direction.header.frame_id = lscene->getPlanningFrame();
452  g.post_grasp_retreat.direction.vector.z = 1.0;
453  g.post_grasp_retreat.min_distance = 0.1;
454  g.post_grasp_retreat.desired_distance = 0.2;
455 
456  if (lscene->getRobotModel()->hasEndEffector(goal.end_effector))
457  {
458  g.pre_grasp_posture.joint_names = lscene->getRobotModel()->getEndEffector(goal.end_effector)->getJointModelNames();
459  g.pre_grasp_posture.points.resize(1);
460  g.pre_grasp_posture.points[0].positions.resize(g.pre_grasp_posture.joint_names.size(),
461  std::numeric_limits<double>::max());
462 
463  g.grasp_posture.joint_names = g.pre_grasp_posture.joint_names;
464  g.grasp_posture.points.resize(1);
465  g.grasp_posture.points[0].positions.resize(g.grasp_posture.joint_names.size(), -std::numeric_limits<double>::max());
466  }
467  goal.possible_grasps.push_back(g);
468 }
469 
plan_execution::ExecutableMotionPlan::planning_scene_
planning_scene::PlanningSceneConstPtr planning_scene_
response
const std::string response
move_group::MoveGroupState
MoveGroupState
plan_execution::ExecutableMotionPlan::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
move_group::LOOK
LOOK
move_group::MoveGroupCapability
IDLE
IDLE
move_group::MoveGroupPickPlaceAction::fillGrasps
void fillGrasps(moveit_msgs::PickupGoal &goal)
Definition: pick_place_action_capability.cpp:427
move_group::MoveGroupPickPlaceAction::executePlaceCallbackPlanAndExecute
void executePlaceCallbackPlanAndExecute(const moveit_msgs::PlaceGoalConstPtr &goal, moveit_msgs::PlaceResult &action_res)
Definition: pick_place_action_capability.cpp:288
move_group::MoveGroupPickPlaceAction::startPickupExecutionCallback
void startPickupExecutionCallback()
Definition: pick_place_action_capability.cpp:68
plan_execution::PlanExecution::Options
move_group::MoveGroupPickPlaceAction::MoveGroupPickPlaceAction
MoveGroupPickPlaceAction()
Definition: pick_place_action_capability.cpp:42
plan_execution::PlanExecution::Options::replan_
bool replan_
move_group::MoveGroupPickPlaceAction
Definition: pick_place_action_capability.h:81
move_group::MoveGroupPickPlaceAction::setPickupState
void setPickupState(MoveGroupState state)
Definition: pick_place_action_capability.cpp:413
move_group::MoveGroupPickPlaceAction::initialize
void initialize() override
Definition: pick_place_action_capability.cpp:47
move_group::MoveGroupPickPlaceAction::startPickupLookCallback
void startPickupLookCallback()
Definition: pick_place_action_capability.cpp:73
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
plan_with_sensing.h
move_group::MoveGroupPickPlaceAction::planUsingPickPlacePickup
bool planUsingPickPlacePickup(const moveit_msgs::PickupGoal &goal, moveit_msgs::PickupResult *action_res, plan_execution::ExecutableMotionPlan &plan)
Definition: pick_place_action_capability.cpp:168
move_group::MoveGroupPickPlaceAction::executePickupCallback
void executePickupCallback(const moveit_msgs::PickupGoalConstPtr &goal)
Definition: pick_place_action_capability.cpp:321
move_group::MoveGroupPickPlaceAction::setPlaceState
void setPlaceState(MoveGroupState state)
Definition: pick_place_action_capability.cpp:420
plan_execution::ExecutableMotionPlan::plan_components_
std::vector< ExecutableTrajectory > plan_components_
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
move_group::MoveGroupPickPlaceAction::preemptPlaceCallback
void preemptPlaceCallback()
Definition: pick_place_action_capability.cpp:409
move_group::MoveGroupPickPlaceAction::startPlaceExecutionCallback
void startPlaceExecutionCallback()
Definition: pick_place_action_capability.cpp:78
plan_execution::PlanExecution::Options::plan_callback_
ExecutableMotionPlanComputationFn plan_callback_
class_loader.hpp
plan_execution::PlanExecution::Options::replan_delay_
double replan_delay_
move_group::MONITOR
MONITOR
plan_execution::PlanExecution::Options::replan_attempts_
unsigned int replan_attempts_
plan_execution::ExecutableMotionPlan::error_code_
moveit_msgs::MoveItErrorCodes error_code_
move_group::MoveGroupPickPlaceAction::executePlaceCallbackPlanOnly
void executePlaceCallbackPlanOnly(const moveit_msgs::PlaceGoalConstPtr &goal, moveit_msgs::PlaceResult &action_res)
Definition: pick_place_action_capability.cpp:128
move_group::MoveGroupPickPlaceAction::executePickupCallbackPlanAndExecute
void executePickupCallbackPlanAndExecute(const moveit_msgs::PickupGoalConstPtr &goal, moveit_msgs::PickupResult &action_res)
Definition: pick_place_action_capability.cpp:254
plan_execution::PlanExecution::Options::before_execution_callback_
boost::function< void()> before_execution_callback_
plan_execution::ExecutableMotionPlan
planning_scene_monitor::LockedPlanningSceneRO
move_group::MoveGroupPickPlaceAction::planUsingPickPlacePlace
bool planUsingPickPlacePlace(const moveit_msgs::PlaceGoal &goal, moveit_msgs::PlaceResult *action_res, plan_execution::ExecutableMotionPlan &plan)
Definition: pick_place_action_capability.cpp:211
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
move_group::PICKUP_ACTION
static const std::string PICKUP_ACTION
Definition: capability_names.h:75
move_group::MoveGroupPickPlaceAction::executePlaceCallback
void executePlaceCallback(const moveit_msgs::PlaceGoalConstPtr &goal)
Definition: pick_place_action_capability.cpp:368
move_group::MoveGroupPickPlaceAction::startPlaceLookCallback
void startPlaceLookCallback()
Definition: pick_place_action_capability.cpp:83
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::AddIterativeSplineParameterization, planning_request_adapter::PlanningRequestAdapter)
pick_place_action_capability.h
move_group::MoveGroupPickPlaceAction::preemptPickupCallback
void preemptPickupCallback()
Definition: pick_place_action_capability.cpp:405
move_group::PLANNING
PLANNING
capability_names.h
move_group::MoveGroupPickPlaceAction::executePickupCallbackPlanOnly
void executePickupCallbackPlanOnly(const moveit_msgs::PickupGoalConstPtr &goal, moveit_msgs::PickupResult &action_res)
Definition: pick_place_action_capability.cpp:88
plan_execution.h
move_group::PLACE_ACTION
static const std::string PLACE_ACTION
Definition: capability_names.h:76
ros::Time::now
static Time now()


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:33