wrap_python_move_group.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 
47 #include <tf2_eigen/tf2_eigen.h>
50 #include <tf2_ros/buffer.h>
51 
52 #include <boost/python.hpp>
53 #include <eigenpy/eigenpy.hpp>
54 #include <memory>
55 #include <Python.h>
56 
59 namespace bp = boost::python;
60 
62 
63 namespace moveit
64 {
65 namespace planning_interface
66 {
67 class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer, public MoveGroupInterface
68 {
69 public:
70  // ROSInitializer is constructed first, and ensures ros::init() was called, if
71  // needed
72  MoveGroupInterfaceWrapper(const std::string& group_name, const std::string& robot_description,
73  const std::string& ns = "", double wait_for_servers = 5.0)
74  : py_bindings_tools::ROScppInitializer()
75  , MoveGroupInterface(Options(group_name, robot_description, ros::NodeHandle(ns)),
76  std::shared_ptr<tf2_ros::Buffer>(), ros::WallDuration(wait_for_servers))
77  {
78  }
79 
80  bool setJointValueTargetPerJointPythonList(const std::string& joint, bp::list& values)
81  {
82  return setJointValueTarget(joint, py_bindings_tools::doubleFromList(values));
83  }
84 
85  bool setJointValueTargetPythonIterable(bp::object& values)
86  {
87  return setJointValueTarget(py_bindings_tools::doubleFromList(values));
88  }
89 
90  bool setJointValueTargetPythonDict(bp::dict& values)
91  {
92  bp::list k = values.keys();
93  int l = bp::len(k);
94  std::map<std::string, double> v;
95  for (int i = 0; i < l; ++i)
96  v[bp::extract<std::string>(k[i])] = bp::extract<double>(values[k[i]]);
97  return setJointValueTarget(v);
98  }
99 
100  bool setJointValueTargetFromPosePython(const py_bindings_tools::ByteString& pose_str, const std::string& eef,
101  bool approx)
102  {
103  geometry_msgs::Pose pose_msg;
104  py_bindings_tools::deserializeMsg(pose_str, pose_msg);
105  return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
106  }
107 
108  bool setJointValueTargetFromPoseStampedPython(const py_bindings_tools::ByteString& pose_str, const std::string& eef,
109  bool approx)
110  {
111  geometry_msgs::PoseStamped pose_msg;
112  py_bindings_tools::deserializeMsg(pose_str, pose_msg);
113  return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
114  }
115 
116  bool setJointValueTargetFromJointStatePython(const py_bindings_tools::ByteString& js_str)
117  {
118  sensor_msgs::JointState js_msg;
119  py_bindings_tools::deserializeMsg(js_str, js_msg);
120  return setJointValueTarget(js_msg);
121  }
122 
123  bp::list getJointValueTargetPythonList()
124  {
125  std::vector<double> values;
127  bp::list l;
128  for (const double value : values)
129  l.append(value);
130  return l;
131  }
132 
133  py_bindings_tools::ByteString getJointValueTarget()
134  {
135  moveit_msgs::RobotState msg;
139  }
140 
141  void rememberJointValuesFromPythonList(const std::string& string, bp::list& values)
142  {
143  rememberJointValues(string, py_bindings_tools::doubleFromList(values));
144  }
145 
146  const char* getPlanningFrameCStr() const
147  {
148  return getPlanningFrame().c_str();
149  }
150 
151  py_bindings_tools::ByteString getInterfaceDescriptionPython()
152  {
153  moveit_msgs::PlannerInterfaceDescription msg;
154  getInterfaceDescription(msg);
156  }
157 
158  bp::list getActiveJointsList() const
159  {
160  return py_bindings_tools::listFromString(getActiveJoints());
161  }
162 
163  bp::list getJointsList() const
164  {
165  return py_bindings_tools::listFromString(getJoints());
166  }
167 
168  bp::list getVariablesList() const
169  {
170  return py_bindings_tools::listFromString(getVariableNames());
171  }
172 
173  bp::list getCurrentJointValuesList()
174  {
175  return py_bindings_tools::listFromDouble(getCurrentJointValues());
176  }
177 
178  bp::list getRandomJointValuesList()
179  {
180  return py_bindings_tools::listFromDouble(getRandomJointValues());
181  }
182 
183  bp::dict getRememberedJointValuesPython() const
184  {
185  const std::map<std::string, std::vector<double>>& rv = getRememberedJointValues();
186  bp::dict d;
187  for (const std::pair<const std::string, std::vector<double>>& it : rv)
188  d[it.first] = py_bindings_tools::listFromDouble(it.second);
189  return d;
190  }
191 
192  bp::list convertPoseToList(const geometry_msgs::Pose& pose) const
193  {
194  std::vector<double> v(7);
195  v[0] = pose.position.x;
196  v[1] = pose.position.y;
197  v[2] = pose.position.z;
198  v[3] = pose.orientation.x;
199  v[4] = pose.orientation.y;
200  v[5] = pose.orientation.z;
201  v[6] = pose.orientation.w;
203  }
204 
205  bp::list convertTransformToList(const geometry_msgs::Transform& tr) const
206  {
207  std::vector<double> v(7);
208  v[0] = tr.translation.x;
209  v[1] = tr.translation.y;
210  v[2] = tr.translation.z;
211  v[3] = tr.rotation.x;
212  v[4] = tr.rotation.y;
213  v[5] = tr.rotation.z;
214  v[6] = tr.rotation.w;
216  }
217 
218  void convertListToTransform(const bp::list& l, geometry_msgs::Transform& tr) const
219  {
220  std::vector<double> v = py_bindings_tools::doubleFromList(l);
221  tr.translation.x = v[0];
222  tr.translation.y = v[1];
223  tr.translation.z = v[2];
224  tr.rotation.x = v[3];
225  tr.rotation.y = v[4];
226  tr.rotation.z = v[5];
227  tr.rotation.w = v[6];
228  }
229 
230  void convertListToPose(const bp::list& l, geometry_msgs::Pose& p) const
231  {
232  std::vector<double> v = py_bindings_tools::doubleFromList(l);
233  p.position.x = v[0];
234  p.position.y = v[1];
235  p.position.z = v[2];
236  p.orientation.x = v[3];
237  p.orientation.y = v[4];
238  p.orientation.z = v[5];
239  p.orientation.w = v[6];
240  }
241 
242  bp::list getCurrentRPYPython(const std::string& end_effector_link = "")
243  {
244  return py_bindings_tools::listFromDouble(getCurrentRPY(end_effector_link));
245  }
246 
247  bp::list getCurrentPosePython(const std::string& end_effector_link = "")
248  {
249  geometry_msgs::PoseStamped pose = getCurrentPose(end_effector_link);
250  return convertPoseToList(pose.pose);
251  }
252 
253  bp::list getRandomPosePython(const std::string& end_effector_link = "")
254  {
255  geometry_msgs::PoseStamped pose = getRandomPose(end_effector_link);
256  return convertPoseToList(pose.pose);
257  }
258 
259  bp::list getKnownConstraintsList() const
260  {
261  return py_bindings_tools::listFromString(getKnownConstraints());
262  }
263 
264  bool placePose(const std::string& object_name, const bp::list& pose, bool plan_only = false)
265  {
266  geometry_msgs::PoseStamped msg;
267  convertListToPose(pose, msg.pose);
268  msg.header.frame_id = getPoseReferenceFrame();
269  msg.header.stamp = ros::Time::now();
270  GILReleaser gr;
271  return place(object_name, msg, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
272  }
273 
274  bool placePoses(const std::string& object_name, const bp::list& poses_list, bool plan_only = false)
275  {
276  int l = bp::len(poses_list);
277  std::vector<geometry_msgs::PoseStamped> poses(l);
278  for (int i = 0; i < l; ++i)
279  py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(poses_list[i]), poses[i]);
280  GILReleaser gr;
281  return place(object_name, poses, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
282  }
283 
284  bool placeLocation(const std::string& object_name, const py_bindings_tools::ByteString& location_str,
285  bool plan_only = false)
286  {
287  std::vector<moveit_msgs::PlaceLocation> locations(1);
288  py_bindings_tools::deserializeMsg(location_str, locations[0]);
289  GILReleaser gr;
290  return place(object_name, std::move(locations), plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
291  }
292 
293  bool placeLocations(const std::string& object_name, const bp::list& location_list, bool plan_only = false)
294  {
295  int l = bp::len(location_list);
296  std::vector<moveit_msgs::PlaceLocation> locations(l);
297  for (int i = 0; i < l; ++i)
298  py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(location_list[i]), locations[i]);
299  GILReleaser gr;
300  return place(object_name, std::move(locations), plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
301  }
302 
303  bool placeAnywhere(const std::string& object_name, bool plan_only = false)
304  {
305  GILReleaser gr;
306  return place(object_name, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
307  }
308 
309  void convertListToArrayOfPoses(const bp::list& poses, std::vector<geometry_msgs::Pose>& msg)
310  {
311  int l = bp::len(poses);
312  for (int i = 0; i < l; ++i)
313  {
314  const bp::list& pose = bp::extract<bp::list>(poses[i]);
315  std::vector<double> v = py_bindings_tools::doubleFromList(pose);
316  if (v.size() == 6 || v.size() == 7)
317  {
318  Eigen::Isometry3d p;
319  if (v.size() == 6)
320  {
321  tf2::Quaternion tq;
322  tq.setRPY(v[3], v[4], v[5]);
323  Eigen::Quaterniond eq;
324  tf2::convert(tq, eq);
325  p = Eigen::Isometry3d(eq);
326  }
327  else
328  p = Eigen::Isometry3d(Eigen::Quaterniond(v[6], v[3], v[4], v[5]));
329  p.translation() = Eigen::Vector3d(v[0], v[1], v[2]);
330  geometry_msgs::Pose pm = tf2::toMsg(p);
331  msg.push_back(pm);
332  }
333  else
334  ROS_WARN("Incorrect number of values for a pose: %u", (unsigned int)v.size());
335  }
336  }
337 
338  bp::dict getCurrentStateBoundedPython()
339  {
340  moveit::core::RobotStatePtr current = getCurrentState();
341  current->enforceBounds();
342  moveit_msgs::RobotState rsmv;
344  bp::dict output;
345  for (size_t x = 0; x < rsmv.joint_state.name.size(); ++x)
346  output[rsmv.joint_state.name[x]] = rsmv.joint_state.position[x];
347  return output;
348  }
349 
350  py_bindings_tools::ByteString getCurrentStatePython()
351  {
352  moveit::core::RobotStatePtr current_state = getCurrentState();
353  moveit_msgs::RobotState state_message;
354  moveit::core::robotStateToRobotStateMsg(*current_state, state_message);
355  return py_bindings_tools::serializeMsg(state_message);
356  }
357 
358  void setStartStatePython(const py_bindings_tools::ByteString& msg_str)
359  {
360  moveit_msgs::RobotState msg;
361  py_bindings_tools::deserializeMsg(msg_str, msg);
362  setStartState(msg);
363  }
364 
365  bool setPoseTargetsPython(bp::list& poses, const std::string& end_effector_link = "")
366  {
367  std::vector<geometry_msgs::Pose> msg;
368  convertListToArrayOfPoses(poses, msg);
369  return setPoseTargets(msg, end_effector_link);
370  }
371  py_bindings_tools::ByteString getPoseTargetPython(const std::string& end_effector_link)
372  {
373  geometry_msgs::PoseStamped pose = moveit::planning_interface::MoveGroupInterface::getPoseTarget(end_effector_link);
374  return py_bindings_tools::serializeMsg(pose);
375  }
376 
377  bool setPoseTargetPython(bp::list& pose, const std::string& end_effector_link = "")
378  {
379  std::vector<double> v = py_bindings_tools::doubleFromList(pose);
380  geometry_msgs::Pose msg;
381  if (v.size() == 6)
382  {
384  q.setRPY(v[3], v[4], v[5]);
385  tf2::convert(q, msg.orientation);
386  }
387  else if (v.size() == 7)
388  {
389  msg.orientation.x = v[3];
390  msg.orientation.y = v[4];
391  msg.orientation.z = v[5];
392  msg.orientation.w = v[6];
393  }
394  else
395  {
396  ROS_ERROR("Pose description expected to consist of either 6 or 7 values");
397  return false;
398  }
399  msg.position.x = v[0];
400  msg.position.y = v[1];
401  msg.position.z = v[2];
402  return setPoseTarget(msg, end_effector_link);
403  }
404 
405  const char* getEndEffectorLinkCStr() const
406  {
407  return getEndEffectorLink().c_str();
408  }
409 
410  const char* getPoseReferenceFrameCStr() const
411  {
412  return getPoseReferenceFrame().c_str();
413  }
414 
415  const char* getNameCStr() const
416  {
417  return getName().c_str();
418  }
419 
420  const char* getPlannerIdCStr() const
421  {
422  return getPlannerId().c_str();
423  }
424 
425  const char* getPlanningPipelineIdCStr() const
426  {
427  return getPlanningPipelineId().c_str();
428  }
429 
430  bp::dict getNamedTargetValuesPython(const std::string& name)
431  {
432  bp::dict output;
433  std::map<std::string, double> positions = getNamedTargetValues(name);
434  std::map<std::string, double>::iterator iterator;
435 
436  for (iterator = positions.begin(); iterator != positions.end(); ++iterator)
437  output[iterator->first] = iterator->second;
438  return output;
439  }
440 
441  bp::list getNamedTargetsPython()
442  {
443  return py_bindings_tools::listFromString(getNamedTargets());
444  }
445 
446  bool movePython()
447  {
448  GILReleaser gr;
449  return move() == moveit::core::MoveItErrorCode::SUCCESS;
450  }
451 
452  bool asyncMovePython()
453  {
454  return asyncMove() == moveit::core::MoveItErrorCode::SUCCESS;
455  }
456 
457  bool attachObjectPython(const std::string& object_name, const std::string& link_name, const bp::list& touch_links)
458  {
459  return attachObject(object_name, link_name, py_bindings_tools::stringFromList(touch_links));
460  }
461 
462  bool executePython(const py_bindings_tools::ByteString& plan_str)
463  {
464  MoveGroupInterface::Plan plan;
465  py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
466  GILReleaser gr;
467  return execute(plan) == moveit::core::MoveItErrorCode::SUCCESS;
468  }
469 
470  bool asyncExecutePython(const py_bindings_tools::ByteString& plan_str)
471  {
472  MoveGroupInterface::Plan plan;
473  py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
474  return asyncExecute(plan) == moveit::core::MoveItErrorCode::SUCCESS;
475  }
476 
477  bp::tuple planPython()
478  {
479  MoveGroupInterface::Plan plan;
480  moveit_msgs::MoveItErrorCodes res;
481  {
482  GILReleaser gr;
484  }
485  return bp::make_tuple(py_bindings_tools::serializeMsg(res), py_bindings_tools::serializeMsg(plan.trajectory_),
486  plan.planning_time_);
487  }
488 
489  py_bindings_tools::ByteString constructMotionPlanRequestPython()
490  {
491  moveit_msgs::MotionPlanRequest request;
492  constructMotionPlanRequest(request);
493  return py_bindings_tools::serializeMsg(request);
494  }
495 
496  bp::tuple computeCartesianPathPython(const bp::list& waypoints, double eef_step, bool avoid_collisions)
497  {
498  moveit_msgs::Constraints path_constraints_tmp;
499  return doComputeCartesianPathPython(waypoints, eef_step, avoid_collisions, path_constraints_tmp);
500  }
501 
502  bp::tuple computeCartesianPathConstrainedPython(const bp::list& waypoints, double eef_step, bool avoid_collisions,
503  const py_bindings_tools::ByteString& path_constraints_str)
504  {
505  moveit_msgs::Constraints path_constraints;
506  py_bindings_tools::deserializeMsg(path_constraints_str, path_constraints);
507  return doComputeCartesianPathPython(waypoints, eef_step, avoid_collisions, path_constraints);
508  }
509 
510  bp::tuple doComputeCartesianPathPython(const bp::list& waypoints, double eef_step, bool avoid_collisions,
511  const moveit_msgs::Constraints& path_constraints)
512  {
513  std::vector<geometry_msgs::Pose> poses;
514  convertListToArrayOfPoses(waypoints, poses);
515  moveit_msgs::RobotTrajectory trajectory;
516  double fraction;
517  {
518  GILReleaser gr;
519  fraction = computeCartesianPath(poses, eef_step, trajectory, path_constraints, avoid_collisions);
520  }
521  return bp::make_tuple(py_bindings_tools::serializeMsg(trajectory), fraction);
522  }
523 
524  int pickGrasp(const std::string& object, const py_bindings_tools::ByteString& grasp_str, bool plan_only = false)
525  {
526  moveit_msgs::Grasp grasp;
527  py_bindings_tools::deserializeMsg(grasp_str, grasp);
528  GILReleaser gr;
529  return pick(object, grasp, plan_only).val;
530  }
531 
532  int pickGrasps(const std::string& object, const bp::list& grasp_list, bool plan_only = false)
533  {
534  int l = bp::len(grasp_list);
535  std::vector<moveit_msgs::Grasp> grasps(l);
536  for (int i = 0; i < l; ++i)
537  py_bindings_tools::deserializeMsg(py_bindings_tools::ByteString(grasp_list[i]), grasps[i]);
538  GILReleaser gr;
539  return pick(object, std::move(grasps), plan_only).val;
540  }
541 
542  void setPathConstraintsFromMsg(const py_bindings_tools::ByteString& constraints_str)
543  {
544  moveit_msgs::Constraints constraints_msg;
545  py_bindings_tools::deserializeMsg(constraints_str, constraints_msg);
546  setPathConstraints(constraints_msg);
547  }
548 
549  py_bindings_tools::ByteString getPathConstraintsPython()
550  {
551  moveit_msgs::Constraints constraints_msg(getPathConstraints());
552  return py_bindings_tools::serializeMsg(constraints_msg);
553  }
554 
555  void setTrajectoryConstraintsFromMsg(const py_bindings_tools::ByteString& constraints_str)
556  {
557  moveit_msgs::TrajectoryConstraints constraints_msg;
558  py_bindings_tools::deserializeMsg(constraints_str, constraints_msg);
559  setTrajectoryConstraints(constraints_msg);
560  }
561 
562  py_bindings_tools::ByteString getTrajectoryConstraintsPython()
563  {
564  moveit_msgs::TrajectoryConstraints constraints_msg(getTrajectoryConstraints());
565  return py_bindings_tools::serializeMsg(constraints_msg);
566  }
567 
568  py_bindings_tools::ByteString retimeTrajectory(const py_bindings_tools::ByteString& ref_state_str,
569  const py_bindings_tools::ByteString& traj_str,
570  double velocity_scaling_factor, double acceleration_scaling_factor,
571  const std::string& algorithm)
572  {
573  // Convert reference state message to object
574  moveit_msgs::RobotState ref_state_msg;
575  py_bindings_tools::deserializeMsg(ref_state_str, ref_state_msg);
576  moveit::core::RobotState ref_state_obj(getRobotModel());
577  if (moveit::core::robotStateMsgToRobotState(ref_state_msg, ref_state_obj, true))
578  {
579  // Convert trajectory message to object
580  moveit_msgs::RobotTrajectory traj_msg;
581  py_bindings_tools::deserializeMsg(traj_str, traj_msg);
582  bool algorithm_found = true;
583  {
584  GILReleaser gr;
585  robot_trajectory::RobotTrajectory traj_obj(getRobotModel(), getName());
586  traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);
587 
588  // Do the actual retiming
589  if (algorithm == "iterative_time_parameterization")
590  {
592  time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
593  }
594  else if (algorithm == "iterative_spline_parameterization")
595  {
597  time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
598  }
599  else if (algorithm == "time_optimal_trajectory_generation")
600  {
602  time_param.computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
603  }
604  else
605  {
606  ROS_ERROR_STREAM_NAMED("move_group_py", "Unknown time parameterization algorithm: " << algorithm);
607  algorithm_found = false;
608  traj_msg = moveit_msgs::RobotTrajectory();
609  }
610 
611  if (algorithm_found)
612  // Convert the retimed trajectory back into a message
613  traj_obj.getRobotTrajectoryMsg(traj_msg);
614  }
615  return py_bindings_tools::serializeMsg(traj_msg);
616  }
617  else
618  {
619  ROS_ERROR("Unable to convert RobotState message to RobotState instance.");
620  return py_bindings_tools::ByteString("");
621  }
622  }
623 
624  Eigen::MatrixXd getJacobianMatrixPython(const bp::list& joint_values, const bp::object& reference_point = bp::object())
625  {
626  const std::vector<double> v = py_bindings_tools::doubleFromList(joint_values);
627  std::vector<double> ref;
628  if (reference_point.is_none())
629  ref = { 0.0, 0.0, 0.0 };
630  else
631  ref = py_bindings_tools::doubleFromList(reference_point);
632  if (ref.size() != 3)
633  throw std::invalid_argument("reference point needs to have 3 elements, got " + std::to_string(ref.size()));
634 
635  moveit::core::RobotState state(getRobotModel());
636  state.setToDefaultValues();
637  auto group = state.getJointModelGroup(getName());
638  state.setJointGroupPositions(group, v);
639  return state.getJacobian(group, Eigen::Map<Eigen::Vector3d>(&ref[0]));
640  }
641 
642  py_bindings_tools::ByteString enforceBoundsPython(const py_bindings_tools::ByteString& msg_str)
643  {
644  moveit_msgs::RobotState state_msg;
645  py_bindings_tools::deserializeMsg(msg_str, state_msg);
646  moveit::core::RobotState state(getRobotModel());
647  if (moveit::core::robotStateMsgToRobotState(state_msg, state, true))
648  {
649  state.enforceBounds();
650  moveit::core::robotStateToRobotStateMsg(state, state_msg);
651  return py_bindings_tools::serializeMsg(state_msg);
652  }
653  else
654  {
655  ROS_ERROR("Unable to convert RobotState message to RobotState instance.");
656  return py_bindings_tools::ByteString("");
657  }
658  }
659 };
660 
661 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getJacobianMatrixOverloads, getJacobianMatrixPython, 1, 2)
662 
663 static void wrap_move_group_interface()
664 {
666 
667  bp::class_<MoveGroupInterfaceWrapper, boost::noncopyable> move_group_interface_class(
668  "MoveGroupInterface", bp::init<std::string, std::string, bp::optional<std::string, double>>());
669 
670  move_group_interface_class.def("async_move", &MoveGroupInterfaceWrapper::asyncMovePython);
671  move_group_interface_class.def("move", &MoveGroupInterfaceWrapper::movePython);
672  move_group_interface_class.def("execute", &MoveGroupInterfaceWrapper::executePython);
673  move_group_interface_class.def("async_execute", &MoveGroupInterfaceWrapper::asyncExecutePython);
674  moveit::core::MoveItErrorCode (MoveGroupInterfaceWrapper::*pick_1)(const std::string&, bool) =
675  &MoveGroupInterfaceWrapper::pick;
676  move_group_interface_class.def("pick", pick_1);
677  move_group_interface_class.def("pick", &MoveGroupInterfaceWrapper::pickGrasp);
678  move_group_interface_class.def("pick", &MoveGroupInterfaceWrapper::pickGrasps);
679  move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placePose);
680  move_group_interface_class.def("place_poses_list", &MoveGroupInterfaceWrapper::placePoses);
681  move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placeLocation);
682  move_group_interface_class.def("place_locations_list", &MoveGroupInterfaceWrapper::placeLocations);
683  move_group_interface_class.def("place", &MoveGroupInterfaceWrapper::placeAnywhere);
684  move_group_interface_class.def("stop", &MoveGroupInterfaceWrapper::stop);
685 
686  move_group_interface_class.def("get_name", &MoveGroupInterfaceWrapper::getNameCStr);
687  move_group_interface_class.def("get_planning_frame", &MoveGroupInterfaceWrapper::getPlanningFrameCStr);
688  move_group_interface_class.def("get_interface_description", &MoveGroupInterfaceWrapper::getInterfaceDescriptionPython);
689 
690  move_group_interface_class.def("get_joints", &MoveGroupInterfaceWrapper::getJointsList);
691  move_group_interface_class.def("get_variables", &MoveGroupInterfaceWrapper::getVariablesList);
692  move_group_interface_class.def("get_active_joints", &MoveGroupInterfaceWrapper::getActiveJointsList);
693  move_group_interface_class.def("get_variable_count", &MoveGroupInterfaceWrapper::getVariableCount);
694  move_group_interface_class.def("allow_looking", &MoveGroupInterfaceWrapper::allowLooking);
695  move_group_interface_class.def("allow_replanning", &MoveGroupInterfaceWrapper::allowReplanning);
696 
697  move_group_interface_class.def("set_pose_reference_frame", &MoveGroupInterfaceWrapper::setPoseReferenceFrame);
698 
699  move_group_interface_class.def("set_pose_reference_frame", &MoveGroupInterfaceWrapper::setPoseReferenceFrame);
700  move_group_interface_class.def("set_end_effector_link", &MoveGroupInterfaceWrapper::setEndEffectorLink);
701  move_group_interface_class.def("get_end_effector_link", &MoveGroupInterfaceWrapper::getEndEffectorLinkCStr);
702  move_group_interface_class.def("get_pose_reference_frame", &MoveGroupInterfaceWrapper::getPoseReferenceFrameCStr);
703 
704  move_group_interface_class.def("set_pose_target", &MoveGroupInterfaceWrapper::setPoseTargetPython);
705 
706  move_group_interface_class.def("set_pose_targets", &MoveGroupInterfaceWrapper::setPoseTargetsPython);
707 
708  move_group_interface_class.def("set_position_target", &MoveGroupInterfaceWrapper::setPositionTarget);
709  move_group_interface_class.def("set_rpy_target", &MoveGroupInterfaceWrapper::setRPYTarget);
710  move_group_interface_class.def("set_orientation_target", &MoveGroupInterfaceWrapper::setOrientationTarget);
711 
712  move_group_interface_class.def("get_current_pose", &MoveGroupInterfaceWrapper::getCurrentPosePython);
713  move_group_interface_class.def("get_current_rpy", &MoveGroupInterfaceWrapper::getCurrentRPYPython);
714 
715  move_group_interface_class.def("get_random_pose", &MoveGroupInterfaceWrapper::getRandomPosePython);
716 
717  move_group_interface_class.def("clear_pose_target", &MoveGroupInterfaceWrapper::clearPoseTarget);
718  move_group_interface_class.def("clear_pose_targets", &MoveGroupInterfaceWrapper::clearPoseTargets);
719 
720  move_group_interface_class.def("set_joint_value_target",
721  &MoveGroupInterfaceWrapper::setJointValueTargetPythonIterable);
722  move_group_interface_class.def("set_joint_value_target", &MoveGroupInterfaceWrapper::setJointValueTargetPythonDict);
723 
724  move_group_interface_class.def("set_joint_value_target",
725  &MoveGroupInterfaceWrapper::setJointValueTargetPerJointPythonList);
726  bool (MoveGroupInterfaceWrapper::*set_joint_value_target_4)(const std::string&, double) =
727  &MoveGroupInterfaceWrapper::setJointValueTarget;
728  move_group_interface_class.def("set_joint_value_target", set_joint_value_target_4);
729 
730  move_group_interface_class.def("set_joint_value_target_from_pose",
731  &MoveGroupInterfaceWrapper::setJointValueTargetFromPosePython);
732  move_group_interface_class.def("set_joint_value_target_from_pose_stamped",
733  &MoveGroupInterfaceWrapper::setJointValueTargetFromPoseStampedPython);
734  move_group_interface_class.def("set_joint_value_target_from_joint_state_message",
735  &MoveGroupInterfaceWrapper::setJointValueTargetFromJointStatePython);
736 
737  move_group_interface_class.def("get_joint_value_target", &MoveGroupInterfaceWrapper::getJointValueTargetPythonList);
738 
739  move_group_interface_class.def("set_named_target", &MoveGroupInterfaceWrapper::setNamedTarget);
740  move_group_interface_class.def("set_random_target", &MoveGroupInterfaceWrapper::setRandomTarget);
741 
742  void (MoveGroupInterfaceWrapper::*remember_joint_values_2)(const std::string&) =
743  &MoveGroupInterfaceWrapper::rememberJointValues;
744  move_group_interface_class.def("remember_joint_values", remember_joint_values_2);
745 
746  move_group_interface_class.def("remember_joint_values", &MoveGroupInterfaceWrapper::rememberJointValuesFromPythonList);
747 
748  move_group_interface_class.def("start_state_monitor", &MoveGroupInterfaceWrapper::startStateMonitor);
749  move_group_interface_class.def("get_current_joint_values", &MoveGroupInterfaceWrapper::getCurrentJointValuesList);
750  move_group_interface_class.def("get_random_joint_values", &MoveGroupInterfaceWrapper::getRandomJointValuesList);
751  move_group_interface_class.def("get_remembered_joint_values",
752  &MoveGroupInterfaceWrapper::getRememberedJointValuesPython);
753 
754  move_group_interface_class.def("forget_joint_values", &MoveGroupInterfaceWrapper::forgetJointValues);
755 
756  move_group_interface_class.def("get_goal_joint_tolerance", &MoveGroupInterfaceWrapper::getGoalJointTolerance);
757  move_group_interface_class.def("get_goal_position_tolerance", &MoveGroupInterfaceWrapper::getGoalPositionTolerance);
758  move_group_interface_class.def("get_goal_orientation_tolerance",
759  &MoveGroupInterfaceWrapper::getGoalOrientationTolerance);
760 
761  move_group_interface_class.def("set_goal_joint_tolerance", &MoveGroupInterfaceWrapper::setGoalJointTolerance);
762  move_group_interface_class.def("set_goal_position_tolerance", &MoveGroupInterfaceWrapper::setGoalPositionTolerance);
763  move_group_interface_class.def("set_goal_orientation_tolerance",
764  &MoveGroupInterfaceWrapper::setGoalOrientationTolerance);
765  move_group_interface_class.def("set_goal_tolerance", &MoveGroupInterfaceWrapper::setGoalTolerance);
766 
767  move_group_interface_class.def("set_start_state_to_current_state",
768  &MoveGroupInterfaceWrapper::setStartStateToCurrentState);
769  move_group_interface_class.def("set_start_state", &MoveGroupInterfaceWrapper::setStartStatePython);
770 
771  bool (MoveGroupInterfaceWrapper::*set_path_constraints_1)(const std::string&) =
772  &MoveGroupInterfaceWrapper::setPathConstraints;
773  move_group_interface_class.def("set_path_constraints", set_path_constraints_1);
774  move_group_interface_class.def("set_path_constraints_from_msg", &MoveGroupInterfaceWrapper::setPathConstraintsFromMsg);
775  move_group_interface_class.def("get_path_constraints", &MoveGroupInterfaceWrapper::getPathConstraintsPython);
776  move_group_interface_class.def("clear_path_constraints", &MoveGroupInterfaceWrapper::clearPathConstraints);
777 
778  move_group_interface_class.def("set_trajectory_constraints_from_msg",
779  &MoveGroupInterfaceWrapper::setTrajectoryConstraintsFromMsg);
780  move_group_interface_class.def("get_trajectory_constraints",
781  &MoveGroupInterfaceWrapper::getTrajectoryConstraintsPython);
782  move_group_interface_class.def("clear_trajectory_constraints", &MoveGroupInterfaceWrapper::clearTrajectoryConstraints);
783  move_group_interface_class.def("get_known_constraints", &MoveGroupInterfaceWrapper::getKnownConstraintsList);
784  move_group_interface_class.def("set_constraints_database", &MoveGroupInterfaceWrapper::setConstraintsDatabase);
785  move_group_interface_class.def("set_workspace", &MoveGroupInterfaceWrapper::setWorkspace);
786  move_group_interface_class.def("set_planning_time", &MoveGroupInterfaceWrapper::setPlanningTime);
787  move_group_interface_class.def("get_planning_time", &MoveGroupInterfaceWrapper::getPlanningTime);
788  move_group_interface_class.def("set_max_velocity_scaling_factor",
789  &MoveGroupInterfaceWrapper::setMaxVelocityScalingFactor);
790  move_group_interface_class.def("set_max_acceleration_scaling_factor",
791  &MoveGroupInterfaceWrapper::setMaxAccelerationScalingFactor);
792  move_group_interface_class.def("limit_max_cartesian_link_speed",
793  &MoveGroupInterfaceWrapper::limitMaxCartesianLinkSpeed);
794  move_group_interface_class.def("clear_max_cartesian_link_speed",
795  &MoveGroupInterfaceWrapper::clearMaxCartesianLinkSpeed);
796  move_group_interface_class.def("set_planner_id", &MoveGroupInterfaceWrapper::setPlannerId);
797  move_group_interface_class.def("get_planner_id", &MoveGroupInterfaceWrapper::getPlannerIdCStr);
798  move_group_interface_class.def("set_planning_pipeline_id", &MoveGroupInterfaceWrapper::setPlanningPipelineId);
799  move_group_interface_class.def("get_planning_pipeline_id", &MoveGroupInterfaceWrapper::getPlanningPipelineIdCStr);
800  move_group_interface_class.def("set_num_planning_attempts", &MoveGroupInterfaceWrapper::setNumPlanningAttempts);
801  move_group_interface_class.def("plan", &MoveGroupInterfaceWrapper::planPython);
802  move_group_interface_class.def("construct_motion_plan_request",
803  &MoveGroupInterfaceWrapper::constructMotionPlanRequestPython);
804  move_group_interface_class.def("compute_cartesian_path", &MoveGroupInterfaceWrapper::computeCartesianPathPython);
805  move_group_interface_class.def("compute_cartesian_path",
806  &MoveGroupInterfaceWrapper::computeCartesianPathConstrainedPython);
807  move_group_interface_class.def("set_support_surface_name", &MoveGroupInterfaceWrapper::setSupportSurfaceName);
808  move_group_interface_class.def("attach_object", &MoveGroupInterfaceWrapper::attachObjectPython);
809  move_group_interface_class.def("detach_object", &MoveGroupInterfaceWrapper::detachObject);
810  move_group_interface_class.def("retime_trajectory", &MoveGroupInterfaceWrapper::retimeTrajectory);
811  move_group_interface_class.def("get_named_targets", &MoveGroupInterfaceWrapper::getNamedTargetsPython);
812  move_group_interface_class.def("get_named_target_values", &MoveGroupInterfaceWrapper::getNamedTargetValuesPython);
813  move_group_interface_class.def("get_current_state_bounded", &MoveGroupInterfaceWrapper::getCurrentStateBoundedPython);
814  move_group_interface_class.def("get_current_state", &MoveGroupInterfaceWrapper::getCurrentStatePython);
815  move_group_interface_class.def("get_jacobian_matrix", &MoveGroupInterfaceWrapper::getJacobianMatrixPython,
816  getJacobianMatrixOverloads());
817  move_group_interface_class.def("enforce_bounds", &MoveGroupInterfaceWrapper::enforceBoundsPython);
818 }
819 } // namespace planning_interface
820 } // namespace moveit
821 
822 BOOST_PYTHON_MODULE(_moveit_move_group_interface)
823 {
824  using namespace moveit::planning_interface;
825  wrap_move_group_interface();
826 }
827 
tf2::convert
void convert(const A &a, B &b)
boost::python
moveit::py_bindings_tools::listFromDouble
boost::python::list listFromDouble(const std::vector< double > &v)
Definition: py_conversions.h:150
eigenpy.hpp
getRandomPose
Eigen::Isometry3d getRandomPose(random_numbers::RandomNumberGenerator &g)
eigenpy::enableEigenPy
void EIGENPY_DLLAPI enableEigenPy()
attachObject
void attachObject()
Definition: demo.cpp:104
tf2_eigen.h
ros
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
trajectory_processing::IterativeParabolicTimeParameterization
ref
list ref
buffer.h
moveit::core::RobotState
robot_trajectory::RobotTrajectory
moveit::planning_interface::MoveGroupInterface::getTargetRobotState
const moveit::core::RobotState & getTargetRobotState() const
Definition: move_group_interface.cpp:1891
roscpp_initializer.h
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(_moveit_roscpp_initializer)
Definition: wrap_python_roscpp_initializer.cpp:50
gil_releaser.h
trajectory_processing::TimeOptimalTrajectoryGeneration
robot_trajectory.h
res
res
moveit::py_bindings_tools::listFromString
boost::python::list listFromString(const std::vector< std::string > &v)
Definition: py_conversions.h:155
moveit::py_bindings_tools::stringFromList
std::vector< std::string > stringFromList(const boost::python::object &values)
Definition: py_conversions.h:145
tf2_ros
py_conversions.h
moveit::planning_interface::MoveGroupInterface::plan
moveit::core::MoveItErrorCode plan(Plan &plan)
Compute a motion plan that takes the group declared in the constructor from the current state to the ...
Definition: move_group_interface.cpp:1618
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
Quaternion.h
serialize_msg.h
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
setup.d
d
Definition: setup.py:4
moveit::planning_interface::MoveItErrorCode
moveit::core::MoveItErrorCode MoveItErrorCode
Definition: move_group_interface.h:130
x
x
q
q
moveit::planning_interface::MoveGroupInterface::getPoseTarget
const geometry_msgs::PoseStamped & getPoseTarget(const std::string &end_effector_link="") const
Definition: move_group_interface.cpp:2001
execute
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
time_optimal_trajectory_generation.h
iterative_spline_parameterization.h
iterative_time_parameterization.h
moveit::py_bindings_tools::GILReleaser
RAII Helper to release the Global Interpreter Lock (GIL)
Definition: gil_releaser.h:118
moveit::planning_interface::MoveGroupInterface::getJointValueTarget
const moveit::core::RobotState & getJointValueTarget() const
Get the currently set joint state goal, replaced by private getTargetRobotState()
Definition: move_group_interface.cpp:1886
trajectory_processing::IterativeSplineParameterization::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit
values
std::vector< double > values
trajectory_processing::IterativeParabolicTimeParameterization::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
moveit::py_bindings_tools::doubleFromList
std::vector< double > doubleFromList(const boost::python::object &values)
Definition: py_conversions.h:140
std
move_group_interface.h
planning_interface
approx
bool approx(S x, S y)
moveit::py_bindings_tools::deserializeMsg
void deserializeMsg(const ByteString &data, T &msg)
Convert a Python Bytestring to a ROS message.
Definition: serialize_msg.h:174
trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
tf2::Quaternion
v
v
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
conversions.h
moveit::planning_interface
Simple interface to MoveIt components.
moveit::py_bindings_tools::serializeMsg
ByteString serializeMsg(const T &msg)
Convert a ROS message to a Python Bytestring.
Definition: serialize_msg.h:167
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
trajectory_processing::IterativeSplineParameterization
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
ros::Time::now
static Time now()
test_cleanup.group
group
Definition: test_cleanup.py:8


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Nov 21 2024 03:25:12