pick_place_task.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019 PickNik LLC.
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *********************************************************************/
32 
33 /* Author: Henning Kayser, Simon Goldstein
34  Desc: A demo to show MoveIt Task Constructor in action
35 */
36 
39 
41 
42 constexpr char LOGNAME[] = "moveit_task_constructor_demo";
43 constexpr char PickPlaceTask::LOGNAME[];
44 
45 void spawnObject(moveit::planning_interface::PlanningSceneInterface& psi, const moveit_msgs::CollisionObject& object) {
46  if (!psi.applyCollisionObject(object))
47  throw std::runtime_error("Failed to spawn object: " + object.id);
48 }
49 
50 moveit_msgs::CollisionObject createTable(const ros::NodeHandle& pnh) {
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;
55  errors += !rosparam_shortcuts::get(LOGNAME, pnh, "table_name", table_name);
56  errors += !rosparam_shortcuts::get(LOGNAME, pnh, "table_reference_frame", table_reference_frame);
57  errors += !rosparam_shortcuts::get(LOGNAME, pnh, "table_dimensions", table_dimensions);
58  errors += !rosparam_shortcuts::get(LOGNAME, pnh, "table_pose", pose);
60 
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]; // align surface with world
68  object.primitive_poses.push_back(pose);
69  return object;
70 }
71 
72 moveit_msgs::CollisionObject createObject(const ros::NodeHandle& pnh) {
73  std::string object_name, object_reference_frame;
74  std::vector<double> object_dimensions;
75  geometry_msgs::Pose pose;
76  std::size_t error = 0;
77  error += !rosparam_shortcuts::get(LOGNAME, pnh, "object_name", object_name);
78  error += !rosparam_shortcuts::get(LOGNAME, pnh, "object_reference_frame", object_reference_frame);
79  error += !rosparam_shortcuts::get(LOGNAME, pnh, "object_dimensions", object_dimensions);
80  error += !rosparam_shortcuts::get(LOGNAME, pnh, "object_pose", pose);
82 
83  moveit_msgs::CollisionObject object;
84  object.id = object_name;
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);
91  return object;
92 }
93 
95  // Add table and object to planning scene
96  ros::Duration(1.0).sleep(); // Wait for ApplyPlanningScene service
98  if (pnh.param("spawn_table", true))
101 }
102 
103 PickPlaceTask::PickPlaceTask(const std::string& task_name, const ros::NodeHandle& pnh)
104  : pnh_(pnh), task_name_(task_name) {
105  loadParameters();
106 }
107 
108 void PickPlaceTask::loadParameters() {
109  /****************************************************
110  * *
111  * Load Parameters *
112  * *
113  ***************************************************/
114  ROS_INFO_NAMED(LOGNAME, "Loading task parameters");
115 
116  // Planning group properties
117  size_t errors = 0;
118  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "arm_group_name", arm_group_name_);
119  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "hand_group_name", hand_group_name_);
120  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "eef_name", eef_name_);
121  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "hand_frame", hand_frame_);
122  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "world_frame", world_frame_);
123  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "grasp_frame_transform", grasp_frame_transform_);
124 
125  // Predefined pose targets
126  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "hand_open_pose", hand_open_pose_);
127  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "hand_close_pose", hand_close_pose_);
128  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "arm_home_pose", arm_home_pose_);
129 
130  // Target object
131  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "object_name", object_name_);
132  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "object_dimensions", object_dimensions_);
133  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "object_reference_frame", object_reference_frame_);
134  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "surface_link", surface_link_);
135  support_surfaces_ = { surface_link_ };
136 
137  // Pick/Place metrics
138  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "approach_object_min_dist", approach_object_min_dist_);
139  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "approach_object_max_dist", approach_object_max_dist_);
140  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "lift_object_min_dist", lift_object_min_dist_);
141  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "lift_object_max_dist", lift_object_max_dist_);
142  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "place_surface_offset", place_surface_offset_);
143  errors += !rosparam_shortcuts::get(LOGNAME, pnh_, "place_pose", place_pose_);
145 }
146 
147 // Initialize the task pipeline, defining individual movement stages
148 bool PickPlaceTask::init() {
149  ROS_INFO_NAMED(LOGNAME, "Initializing task pipeline");
150  const std::string object = object_name_;
151 
152  // Reset ROS introspection before constructing the new object
153  // TODO(v4hn): global storage for Introspection services to enable one-liner
154  task_.reset();
155  task_.reset(new moveit::task_constructor::Task());
156 
157  // Individual movement stages are collected within the Task object
158  Task& t = *task_;
159  t.stages()->setName(task_name_);
160  t.loadRobotModel();
161 
162  /* Create planners used in various stages. Various options are available,
163  namely Cartesian, MoveIt pipeline, and joint interpolation. */
164  // Sampling planner
165  auto sampling_planner = std::make_shared<solvers::PipelinePlanner>();
166  sampling_planner->setProperty("goal_joint_tolerance", 1e-5);
167 
168  // Cartesian planner
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);
173 
174  // Set task properties
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_);
180 
181  /****************************************************
182  * *
183  * Current State *
184  * *
185  ***************************************************/
186  {
187  auto current_state = std::make_unique<stages::CurrentState>("current state");
188 
189  // Verify that object is not attached
190  auto applicability_filter =
191  std::make_unique<stages::PredicateFilter>("applicability test", std::move(current_state));
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";
195  return false;
196  }
197  return true;
198  });
199  t.add(std::move(applicability_filter));
200  }
201 
202  /****************************************************
203  * *
204  * Open Hand *
205  * *
206  ***************************************************/
207  Stage* initial_state_ptr = nullptr;
208  {
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(); // remember start state for monitoring grasp pose generator
213  t.add(std::move(stage));
214  }
215 
216  /****************************************************
217  * *
218  * Move to Pick *
219  * *
220  ***************************************************/
221  // Connect initial open-hand state with pre-grasp pose defined in the following
222  {
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);
228  t.add(std::move(stage));
229  }
230 
231  /****************************************************
232  * *
233  * Pick Object *
234  * *
235  ***************************************************/
236  Stage* pick_stage_ptr = nullptr;
237  {
238  // A SerialContainer combines several sub-stages, here for picking the object
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" });
242 
243  /****************************************************
244  ---- * Approach Object *
245  ***************************************************/
246  {
247  // Move the eef link forward along its z-axis by an amount within the given min-max range
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_); // link to perform IK for
251  stage->properties().configureInitFrom(Stage::PARENT, { "group" }); // inherit group from parent stage
252  stage->setMinMaxDistance(approach_object_min_dist_, approach_object_max_dist_);
253 
254  // Set hand forward direction
255  geometry_msgs::Vector3Stamped vec;
256  vec.header.frame_id = hand_frame_;
257  vec.vector.z = 1.0;
258  stage->setDirection(vec);
259  grasp->insert(std::move(stage));
260  }
261 
262  /****************************************************
263  ---- * Generate Grasp Pose *
264  ***************************************************/
265  {
266  // Sample grasp pose candidates in angle increments around the z-axis of the object
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); // object to sample grasps for
272  stage->setAngleDelta(M_PI / 12);
273  stage->setMonitoredStage(initial_state_ptr); // hook into successful initial-phase solutions
274 
275  // Compute IK for sampled grasp poses
276  auto wrapper = std::make_unique<stages::ComputeIK>("grasp pose IK", std::move(stage));
277  wrapper->setMaxIKSolutions(8); // limit number of solutions
278  wrapper->setMinSolutionDistance(1.0);
279  wrapper->setIKFrame(grasp_frame_transform_, hand_frame_); // define virtual frame to reach the target_pose
280  wrapper->properties().configureInitFrom(Stage::PARENT, { "eef", "group" }); // inherit properties from parent
281  wrapper->properties().configureInitFrom(Stage::INTERFACE,
282  { "target_pose" }); // inherit property from child solution
283  grasp->insert(std::move(wrapper));
284  }
285 
286  /****************************************************
287  ---- * Allow Collision (hand object) *
288  ***************************************************/
289  {
290  // Modify planning scene (w/o altering the robot's pose) to allow touching the object for picking
291  auto stage = std::make_unique<stages::ModifyPlanningScene>("allow collision (hand,object)");
292  stage->allowCollisions(
293  object, t.getRobotModel()->getJointModelGroup(hand_group_name_)->getLinkModelNamesWithCollisionGeometry(),
294  true);
295  grasp->insert(std::move(stage));
296  }
297 
298  /****************************************************
299  ---- * Close Hand *
300  ***************************************************/
301  {
302  auto stage = std::make_unique<stages::MoveTo>("close hand", sampling_planner);
303  stage->setGroup(hand_group_name_);
304  stage->setGoal(hand_close_pose_);
305  grasp->insert(std::move(stage));
306  }
307 
308  /****************************************************
309  .... * Attach Object *
310  ***************************************************/
311  {
312  auto stage = std::make_unique<stages::ModifyPlanningScene>("attach object");
313  stage->attachObject(object, hand_frame_); // attach object to hand_frame_
314  grasp->insert(std::move(stage));
315  }
316 
317  /****************************************************
318  .... * Allow collision (object support) *
319  ***************************************************/
320  {
321  auto stage = std::make_unique<stages::ModifyPlanningScene>("allow collision (object,support)");
322  stage->allowCollisions({ object }, support_surfaces_, true);
323  grasp->insert(std::move(stage));
324  }
325 
326  /****************************************************
327  .... * Lift object *
328  ***************************************************/
329  {
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");
335 
336  // Set upward direction
337  geometry_msgs::Vector3Stamped vec;
338  vec.header.frame_id = world_frame_;
339  vec.vector.z = 1.0;
340  stage->setDirection(vec);
341  grasp->insert(std::move(stage));
342  }
343 
344  /****************************************************
345  .... * Forbid collision (object support) *
346  ***************************************************/
347  {
348  auto stage = std::make_unique<stages::ModifyPlanningScene>("forbid collision (object,support)");
349  stage->allowCollisions({ object }, support_surfaces_, false);
350  grasp->insert(std::move(stage));
351  }
352 
353  pick_stage_ptr = grasp.get(); // remember for monitoring place pose generator
354 
355  // Add grasp container to task
356  t.add(std::move(grasp));
357  }
358 
359  /******************************************************
360  * *
361  * Move to Place *
362  * *
363  *****************************************************/
364  {
365  // Connect the grasped state to the pre-place state, i.e. realize the object transport
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);
370  t.add(std::move(stage));
371  }
372 
373  /******************************************************
374  * *
375  * Place Object *
376  * *
377  *****************************************************/
378  // All placing sub-stages are collected within a serial container again
379  {
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" });
383 
384  /******************************************************
385  ---- * Lower Object *
386  *****************************************************/
387  {
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);
393 
394  // Set downward direction
395  geometry_msgs::Vector3Stamped vec;
396  vec.header.frame_id = world_frame_;
397  vec.vector.z = -1.0;
398  stage->setDirection(vec);
399  place->insert(std::move(stage));
400  }
401 
402  /******************************************************
403  ---- * Generate Place Pose *
404  *****************************************************/
405  {
406  // Generate Place Pose
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);
411 
412  // Set target pose
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_;
417  stage->setPose(p);
418  stage->setMonitoredStage(pick_stage_ptr); // hook into successful pick solutions
419 
420  // Compute IK
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" });
426  place->insert(std::move(wrapper));
427  }
428 
429  /******************************************************
430  ---- * Open Hand *
431  *****************************************************/
432  {
433  auto stage = std::make_unique<stages::MoveTo>("open hand", sampling_planner);
434  stage->setGroup(hand_group_name_);
435  stage->setGoal(hand_open_pose_);
436  place->insert(std::move(stage));
437  }
438 
439  /******************************************************
440  ---- * Forbid collision (hand, object) *
441  *****************************************************/
442  {
443  auto stage = std::make_unique<stages::ModifyPlanningScene>("forbid collision (hand,object)");
444  stage->allowCollisions(object_name_, *t.getRobotModel()->getJointModelGroup(hand_group_name_), false);
445  place->insert(std::move(stage));
446  }
447 
448  /******************************************************
449  ---- * Detach Object *
450  *****************************************************/
451  {
452  auto stage = std::make_unique<stages::ModifyPlanningScene>("detach object");
453  stage->detachObject(object_name_, hand_frame_);
454  place->insert(std::move(stage));
455  }
456 
457  /******************************************************
458  ---- * Retreat Motion *
459  *****************************************************/
460  {
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_;
468  vec.vector.z = -1.0;
469  stage->setDirection(vec);
470  place->insert(std::move(stage));
471  }
472 
473  // Add place container to task
474  t.add(std::move(place));
475  }
476 
477  /******************************************************
478  * *
479  * Move to Home *
480  * *
481  *****************************************************/
482  {
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);
487  t.add(std::move(stage));
488  }
489 
490  // prepare Task structure for planning
491  try {
492  t.init();
493  } catch (InitStageException& e) {
494  ROS_ERROR_STREAM_NAMED(LOGNAME, "Initialization failed: " << e);
495  return false;
496  }
497 
498  return true;
499 }
500 
501 bool PickPlaceTask::plan() {
502  ROS_INFO_NAMED(LOGNAME, "Start searching for task solutions");
503  int max_solutions = pnh_.param<int>("max_solutions", 10);
504 
505  return static_cast<bool>(task_->plan(max_solutions));
506 }
507 
508 bool PickPlaceTask::execute() {
509  ROS_INFO_NAMED(LOGNAME, "Executing solution trajectory");
510  moveit_msgs::MoveItErrorCodes execute_result;
511 
512  execute_result = task_->execute(*task_->solutions().front());
513 
514  if (execute_result.val != moveit_msgs::MoveItErrorCodes::SUCCESS) {
515  ROS_ERROR_STREAM_NAMED(LOGNAME, "Task execution failed and returned: " << execute_result.val);
516  return false;
517  }
518 
519  return true;
520 }
521 } // namespace moveit_task_constructor_demo
moveit_task_constructor_demo::PickPlaceTask::PickPlaceTask
PickPlaceTask(const std::string &task_name, const ros::NodeHandle &pnh)
Definition: pick_place_task.cpp:133
moveit_task_constructor_demo::spawnObject
void spawnObject(moveit::planning_interface::PlanningSceneInterface &psi, const moveit_msgs::CollisionObject &object)
Definition: pick_place_task.cpp:75
moveit_task_constructor_demo
Definition: pick_place_task.h:63
rosparam_shortcuts::get
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, bool &value)
s
XmlRpcServer s
pickplace.place
place
Definition: pickplace.py:161
properties.stage
stage
Definition: properties.py:83
moveit::planning_interface::PlanningSceneInterface
vec
vec
current_state
Definition: current_state.py:1
moveit_task_constructor_demo::createTable
moveit_msgs::CollisionObject createTable(const ros::NodeHandle &pnh)
Definition: pick_place_task.cpp:80
pickplace.grasp
grasp
Definition: pickplace.py:70
compute_ik.pose
pose
Definition: compute_ik.py:36
moveit::task_constructor::Stage
moveit::task_constructor::Task
moveit_task_constructor_demo::createObject
moveit_msgs::CollisionObject createObject(const ros::NodeHandle &pnh)
Definition: pick_place_task.cpp:102
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
modify_planning_scene.object
object
Definition: modify_planning_scene.py:32
modify_planning_scene.object_name
string object_name
Definition: modify_planning_scene.py:22
properties.p
p
Definition: properties.py:14
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_task_constructor_demo::PickPlaceTask::LOGNAME
static constexpr char LOGNAME[]
Definition: pick_place_task.h:114
rosparam_shortcuts.h
pickplace.psi
psi
Definition: pickplace.py:25
moveit_task_constructor_demo::LOGNAME
constexpr char LOGNAME[]
Definition: pick_place_task.cpp:72
generate_pose.planners
list planners
Definition: generate_pose.py:26
cartesian.move
move
Definition: cartesian.py:34
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Duration::sleep
bool sleep() const
moveit_task_constructor_demo::setupDemoScene
void setupDemoScene(ros::NodeHandle &pnh)
Definition: pick_place_task.cpp:124
t
dictionary t
ros::Duration
rosparam_shortcuts::shutdownIfError
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
pick_place_task.h
moveit::task_constructor::SolutionBase
ros::NodeHandle
error
def error(*args, **kwargs)


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30