52 #include <boost/python.hpp>
67 class MoveGroupInterfaceWrapper :
protected py_bindings_tools::ROScppInitializer,
public MoveGroupInterface
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))
80 bool setJointValueTargetPerJointPythonList(
const std::string& joint, bp::list& values)
85 bool setJointValueTargetPythonIterable(bp::object& values)
90 bool setJointValueTargetPythonDict(bp::dict& values)
92 bp::list k =
values.keys();
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);
100 bool setJointValueTargetFromPosePython(
const py_bindings_tools::ByteString& pose_str,
const std::string& eef,
103 geometry_msgs::Pose pose_msg;
105 return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
108 bool setJointValueTargetFromPoseStampedPython(
const py_bindings_tools::ByteString& pose_str,
const std::string& eef,
111 geometry_msgs::PoseStamped pose_msg;
113 return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
116 bool setJointValueTargetFromJointStatePython(
const py_bindings_tools::ByteString& js_str)
118 sensor_msgs::JointState js_msg;
120 return setJointValueTarget(js_msg);
123 bp::list getJointValueTargetPythonList()
125 std::vector<double>
values;
128 for (
const double value : values)
133 py_bindings_tools::ByteString getJointValueTarget()
135 moveit_msgs::RobotState msg;
141 void rememberJointValuesFromPythonList(
const std::string&
string, bp::list& values)
146 const char* getPlanningFrameCStr()
const
148 return getPlanningFrame().c_str();
151 py_bindings_tools::ByteString getInterfaceDescriptionPython()
153 moveit_msgs::PlannerInterfaceDescription msg;
154 getInterfaceDescription(msg);
158 bp::list getActiveJointsList()
const
163 bp::list getJointsList()
const
168 bp::list getVariablesList()
const
173 bp::list getCurrentJointValuesList()
178 bp::list getRandomJointValuesList()
183 bp::dict getRememberedJointValuesPython()
const
185 const std::map<std::string, std::vector<double>>& rv = getRememberedJointValues();
187 for (
const std::pair<
const std::string, std::vector<double>>& it : rv)
192 bp::list convertPoseToList(
const geometry_msgs::Pose& pose)
const
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;
205 bp::list convertTransformToList(
const geometry_msgs::Transform& tr)
const
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;
218 void convertListToTransform(
const bp::list& l, geometry_msgs::Transform& tr)
const
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];
230 void convertListToPose(
const bp::list& l, geometry_msgs::Pose& p)
const
236 p.orientation.x =
v[3];
237 p.orientation.y =
v[4];
238 p.orientation.z =
v[5];
239 p.orientation.w =
v[6];
242 bp::list getCurrentRPYPython(
const std::string& end_effector_link =
"")
247 bp::list getCurrentPosePython(
const std::string& end_effector_link =
"")
249 geometry_msgs::PoseStamped pose = getCurrentPose(end_effector_link);
250 return convertPoseToList(pose.pose);
253 bp::list getRandomPosePython(
const std::string& end_effector_link =
"")
255 geometry_msgs::PoseStamped pose =
getRandomPose(end_effector_link);
256 return convertPoseToList(pose.pose);
259 bp::list getKnownConstraintsList()
const
264 bool placePose(
const std::string& object_name,
const bp::list& pose,
bool plan_only =
false)
266 geometry_msgs::PoseStamped msg;
267 convertListToPose(pose, msg.pose);
268 msg.header.frame_id = getPoseReferenceFrame();
271 return place(object_name, msg, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
274 bool placePoses(
const std::string& object_name,
const bp::list& poses_list,
bool plan_only =
false)
276 int l = bp::len(poses_list);
277 std::vector<geometry_msgs::PoseStamped> poses(l);
278 for (
int i = 0; i < l; ++i)
281 return place(object_name, poses, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
284 bool placeLocation(
const std::string& object_name,
const py_bindings_tools::ByteString& location_str,
285 bool plan_only =
false)
287 std::vector<moveit_msgs::PlaceLocation> locations(1);
290 return place(object_name, std::move(locations), plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
293 bool placeLocations(
const std::string& object_name,
const bp::list& location_list,
bool plan_only =
false)
295 int l = bp::len(location_list);
296 std::vector<moveit_msgs::PlaceLocation> locations(l);
297 for (
int i = 0; i < l; ++i)
300 return place(object_name, std::move(locations), plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
303 bool placeAnywhere(
const std::string& object_name,
bool plan_only =
false)
306 return place(object_name, plan_only) == moveit::core::MoveItErrorCode::SUCCESS;
309 void convertListToArrayOfPoses(
const bp::list& poses, std::vector<geometry_msgs::Pose>& msg)
311 int l = bp::len(poses);
312 for (
int i = 0; i < l; ++i)
314 const bp::list& pose = bp::extract<bp::list>(poses[i]);
316 if (
v.size() == 6 ||
v.size() == 7)
322 tq.
setRPY(v[3], v[4], v[5]);
323 Eigen::Quaterniond eq;
325 p = Eigen::Isometry3d(eq);
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]);
334 ROS_WARN(
"Incorrect number of values for a pose: %u", (
unsigned int)
v.size());
338 bp::dict getCurrentStateBoundedPython()
340 moveit::core::RobotStatePtr current = getCurrentState();
341 current->enforceBounds();
342 moveit_msgs::RobotState rsmv;
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];
350 py_bindings_tools::ByteString getCurrentStatePython()
352 moveit::core::RobotStatePtr current_state = getCurrentState();
353 moveit_msgs::RobotState state_message;
358 void setStartStatePython(
const py_bindings_tools::ByteString& msg_str)
360 moveit_msgs::RobotState msg;
365 bool setPoseTargetsPython(bp::list& poses,
const std::string& end_effector_link =
"")
367 std::vector<geometry_msgs::Pose> msg;
368 convertListToArrayOfPoses(poses, msg);
369 return setPoseTargets(msg, end_effector_link);
371 py_bindings_tools::ByteString getPoseTargetPython(
const std::string& end_effector_link)
377 bool setPoseTargetPython(bp::list& pose,
const std::string& end_effector_link =
"")
380 geometry_msgs::Pose msg;
384 q.setRPY(v[3], v[4], v[5]);
387 else if (
v.size() == 7)
389 msg.orientation.x =
v[3];
390 msg.orientation.y =
v[4];
391 msg.orientation.z =
v[5];
392 msg.orientation.w =
v[6];
396 ROS_ERROR(
"Pose description expected to consist of either 6 or 7 values");
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);
405 const char* getEndEffectorLinkCStr()
const
407 return getEndEffectorLink().c_str();
410 const char* getPoseReferenceFrameCStr()
const
412 return getPoseReferenceFrame().c_str();
415 const char* getNameCStr()
const
420 const char* getPlannerIdCStr()
const
422 return getPlannerId().c_str();
425 const char* getPlanningPipelineIdCStr()
const
427 return getPlanningPipelineId().c_str();
430 bp::dict getNamedTargetValuesPython(
const std::string& name)
433 std::map<std::string, double> positions = getNamedTargetValues(name);
434 std::map<std::string, double>::iterator iterator;
436 for (iterator = positions.begin(); iterator != positions.end(); ++iterator)
437 output[iterator->first] = iterator->second;
441 bp::list getNamedTargetsPython()
449 return move() == moveit::core::MoveItErrorCode::SUCCESS;
452 bool asyncMovePython()
454 return asyncMove() == moveit::core::MoveItErrorCode::SUCCESS;
457 bool attachObjectPython(
const std::string& object_name,
const std::string& link_name,
const bp::list& touch_links)
462 bool executePython(
const py_bindings_tools::ByteString& plan_str)
464 MoveGroupInterface::Plan plan;
467 return execute(plan) == moveit::core::MoveItErrorCode::SUCCESS;
470 bool asyncExecutePython(
const py_bindings_tools::ByteString& plan_str)
472 MoveGroupInterface::Plan plan;
474 return asyncExecute(plan) == moveit::core::MoveItErrorCode::SUCCESS;
477 bp::tuple planPython()
479 MoveGroupInterface::Plan plan;
480 moveit_msgs::MoveItErrorCodes
res;
486 plan.planning_time_);
489 py_bindings_tools::ByteString constructMotionPlanRequestPython()
491 moveit_msgs::MotionPlanRequest request;
492 constructMotionPlanRequest(request);
496 bp::tuple computeCartesianPathPython(
const bp::list& waypoints,
double eef_step,
bool avoid_collisions)
498 moveit_msgs::Constraints path_constraints_tmp;
499 return doComputeCartesianPathPython(waypoints, eef_step, avoid_collisions, path_constraints_tmp);
502 bp::tuple computeCartesianPathConstrainedPython(
const bp::list& waypoints,
double eef_step,
bool avoid_collisions,
503 const py_bindings_tools::ByteString& path_constraints_str)
505 moveit_msgs::Constraints path_constraints;
507 return doComputeCartesianPathPython(waypoints, eef_step, avoid_collisions, path_constraints);
510 bp::tuple doComputeCartesianPathPython(
const bp::list& waypoints,
double eef_step,
bool avoid_collisions,
511 const moveit_msgs::Constraints& path_constraints)
513 std::vector<geometry_msgs::Pose> poses;
514 convertListToArrayOfPoses(waypoints, poses);
515 moveit_msgs::RobotTrajectory trajectory;
519 fraction = computeCartesianPath(poses, eef_step, trajectory, path_constraints, avoid_collisions);
524 int pickGrasp(
const std::string&
object,
const py_bindings_tools::ByteString& grasp_str,
bool plan_only =
false)
526 moveit_msgs::Grasp grasp;
529 return pick(
object, grasp, plan_only).val;
532 int pickGrasps(
const std::string&
object,
const bp::list& grasp_list,
bool plan_only =
false)
534 int l = bp::len(grasp_list);
535 std::vector<moveit_msgs::Grasp> grasps(l);
536 for (
int i = 0; i < l; ++i)
539 return pick(
object, std::move(grasps), plan_only).val;
542 void setPathConstraintsFromMsg(
const py_bindings_tools::ByteString& constraints_str)
544 moveit_msgs::Constraints constraints_msg;
546 setPathConstraints(constraints_msg);
549 py_bindings_tools::ByteString getPathConstraintsPython()
551 moveit_msgs::Constraints constraints_msg(getPathConstraints());
555 void setTrajectoryConstraintsFromMsg(
const py_bindings_tools::ByteString& constraints_str)
557 moveit_msgs::TrajectoryConstraints constraints_msg;
559 setTrajectoryConstraints(constraints_msg);
562 py_bindings_tools::ByteString getTrajectoryConstraintsPython()
564 moveit_msgs::TrajectoryConstraints constraints_msg(getTrajectoryConstraints());
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)
574 moveit_msgs::RobotState ref_state_msg;
580 moveit_msgs::RobotTrajectory traj_msg;
582 bool algorithm_found =
true;
586 traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);
589 if (algorithm ==
"iterative_time_parameterization")
592 time_param.
computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
594 else if (algorithm ==
"iterative_spline_parameterization")
597 time_param.
computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
599 else if (algorithm ==
"time_optimal_trajectory_generation")
602 time_param.
computeTimeStamps(traj_obj, velocity_scaling_factor, acceleration_scaling_factor);
607 algorithm_found =
false;
608 traj_msg = moveit_msgs::RobotTrajectory();
613 traj_obj.getRobotTrajectoryMsg(traj_msg);
619 ROS_ERROR(
"Unable to convert RobotState message to RobotState instance.");
620 return py_bindings_tools::ByteString(
"");
624 Eigen::MatrixXd getJacobianMatrixPython(
const bp::list& joint_values,
const bp::object& reference_point = bp::object())
627 std::vector<double>
ref;
628 if (reference_point.is_none())
629 ref = { 0.0, 0.0, 0.0 };
633 throw std::invalid_argument(
"reference point needs to have 3 elements, got " + std::to_string(
ref.size()));
636 state.setToDefaultValues();
638 state.setJointGroupPositions(
group, v);
639 return state.getJacobian(
group, Eigen::Map<Eigen::Vector3d>(&ref[0]));
642 py_bindings_tools::ByteString enforceBoundsPython(
const py_bindings_tools::ByteString& msg_str)
644 moveit_msgs::RobotState state_msg;
649 state.enforceBounds();
655 ROS_ERROR(
"Unable to convert RobotState message to RobotState instance.");
656 return py_bindings_tools::ByteString(
"");
661 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getJacobianMatrixOverloads, getJacobianMatrixPython, 1, 2)
663 static
void wrap_move_group_interface()
667 bp::class_<MoveGroupInterfaceWrapper, boost::noncopyable> move_group_interface_class(
668 "MoveGroupInterface", bp::init<std::string, std::string, bp::optional<std::string, double>>());
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);
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);
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);
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);
697 move_group_interface_class.def(
"set_pose_reference_frame", &MoveGroupInterfaceWrapper::setPoseReferenceFrame);
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);
704 move_group_interface_class.def(
"set_pose_target", &MoveGroupInterfaceWrapper::setPoseTargetPython);
706 move_group_interface_class.def(
"set_pose_targets", &MoveGroupInterfaceWrapper::setPoseTargetsPython);
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);
712 move_group_interface_class.def(
"get_current_pose", &MoveGroupInterfaceWrapper::getCurrentPosePython);
713 move_group_interface_class.def(
"get_current_rpy", &MoveGroupInterfaceWrapper::getCurrentRPYPython);
715 move_group_interface_class.def(
"get_random_pose", &MoveGroupInterfaceWrapper::getRandomPosePython);
717 move_group_interface_class.def(
"clear_pose_target", &MoveGroupInterfaceWrapper::clearPoseTarget);
718 move_group_interface_class.def(
"clear_pose_targets", &MoveGroupInterfaceWrapper::clearPoseTargets);
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);
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);
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);
737 move_group_interface_class.def(
"get_joint_value_target", &MoveGroupInterfaceWrapper::getJointValueTargetPythonList);
739 move_group_interface_class.def(
"set_named_target", &MoveGroupInterfaceWrapper::setNamedTarget);
740 move_group_interface_class.def(
"set_random_target", &MoveGroupInterfaceWrapper::setRandomTarget);
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);
746 move_group_interface_class.def(
"remember_joint_values", &MoveGroupInterfaceWrapper::rememberJointValuesFromPythonList);
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);
754 move_group_interface_class.def(
"forget_joint_values", &MoveGroupInterfaceWrapper::forgetJointValues);
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);
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);
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);
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);
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);
825 wrap_move_group_interface();