wrap_python_move_group.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #include <moveit/move_group_interface/move_group.h>
00038 #include <moveit/py_bindings_tools/roscpp_initializer.h>
00039 #include <moveit/py_bindings_tools/py_conversions.h>
00040 #include <moveit/py_bindings_tools/serialize_msg.h>
00041 #include <moveit/robot_state/conversions.h>
00042 #include <moveit/robot_trajectory/robot_trajectory.h>
00043 #include <moveit/trajectory_processing/iterative_time_parameterization.h>
00044 #include <eigen_conversions/eigen_msg.h>
00045 #include <tf_conversions/tf_eigen.h>
00046 
00047 #include <boost/python.hpp>
00048 #include <boost/shared_ptr.hpp>
00049 #include <Python.h>
00050 
00053 namespace bp = boost::python;
00054 
00055 namespace moveit
00056 {
00057 namespace planning_interface
00058 {
00059 class MoveGroupWrapper : protected py_bindings_tools::ROScppInitializer, public MoveGroup
00060 {
00061 public:
00062   // ROSInitializer is constructed first, and ensures ros::init() was called, if needed
00063   MoveGroupWrapper(const std::string& group_name, const std::string& robot_description)
00064     : py_bindings_tools::ROScppInitializer()
00065     , MoveGroup(Options(group_name, robot_description), boost::shared_ptr<tf::Transformer>(), ros::WallDuration(5, 0))
00066   {
00067   }
00068 
00069   bool setJointValueTargetPerJointPythonList(const std::string& joint, bp::list& values)
00070   {
00071     return setJointValueTarget(joint, py_bindings_tools::doubleFromList(values));
00072   }
00073 
00074   bool setJointValueTargetPythonIterable(bp::object& values)
00075   {
00076     return setJointValueTarget(py_bindings_tools::doubleFromList(values));
00077   }
00078 
00079   bool setJointValueTargetPythonDict(bp::dict& values)
00080   {
00081     bp::list k = values.keys();
00082     int l = bp::len(k);
00083     std::map<std::string, double> v;
00084     for (int i = 0; i < l; ++i)
00085       v[bp::extract<std::string>(k[i])] = bp::extract<double>(values[k[i]]);
00086     return setJointValueTarget(v);
00087   }
00088 
00089   bool setJointValueTargetFromPosePython(const std::string& pose_str, const std::string& eef, bool approx)
00090   {
00091     geometry_msgs::Pose pose_msg;
00092     py_bindings_tools::deserializeMsg(pose_str, pose_msg);
00093     return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
00094   }
00095 
00096   bool setJointValueTargetFromPoseStampedPython(const std::string& pose_str, const std::string& eef, bool approx)
00097   {
00098     geometry_msgs::PoseStamped pose_msg;
00099     py_bindings_tools::deserializeMsg(pose_str, pose_msg);
00100     return approx ? setApproximateJointValueTarget(pose_msg, eef) : setJointValueTarget(pose_msg, eef);
00101   }
00102 
00103   bool setJointValueTargetFromJointStatePython(const std::string& js_str)
00104   {
00105     sensor_msgs::JointState js_msg;
00106     py_bindings_tools::deserializeMsg(js_str, js_msg);
00107     return setJointValueTarget(js_msg);
00108   }
00109 
00110   bp::list getJointValueTargetPythonList()
00111   {
00112     const robot_state::RobotState& values = moveit::planning_interface::MoveGroup::getJointValueTarget();
00113     bp::list l;
00114     for (const double *it = values.getVariablePositions(), *end = it + getVariableCount(); it != end; ++it)
00115       l.append(*it);
00116     return l;
00117   }
00118 
00119   void rememberJointValuesFromPythonList(const std::string& string, bp::list& values)
00120   {
00121     rememberJointValues(string, py_bindings_tools::doubleFromList(values));
00122   }
00123 
00124   const char* getPlanningFrameCStr() const
00125   {
00126     return getPlanningFrame().c_str();
00127   }
00128 
00129   bp::list getActiveJointsList() const
00130   {
00131     return py_bindings_tools::listFromString(getActiveJoints());
00132   }
00133 
00134   bp::list getJointsList() const
00135   {
00136     return py_bindings_tools::listFromString(getJoints());
00137   }
00138 
00139   bp::list getCurrentJointValuesList()
00140   {
00141     return py_bindings_tools::listFromDouble(getCurrentJointValues());
00142   }
00143 
00144   bp::list getRandomJointValuesList()
00145   {
00146     return py_bindings_tools::listFromDouble(getRandomJointValues());
00147   }
00148 
00149   bp::dict getRememberedJointValuesPython() const
00150   {
00151     const std::map<std::string, std::vector<double> >& rv = getRememberedJointValues();
00152     bp::dict d;
00153     for (std::map<std::string, std::vector<double> >::const_iterator it = rv.begin(); it != rv.end(); ++it)
00154       d[it->first] = py_bindings_tools::listFromDouble(it->second);
00155     return d;
00156   }
00157 
00158   bp::list convertPoseToList(const geometry_msgs::Pose& pose) const
00159   {
00160     std::vector<double> v(7);
00161     v[0] = pose.position.x;
00162     v[1] = pose.position.y;
00163     v[2] = pose.position.z;
00164     v[3] = pose.orientation.x;
00165     v[4] = pose.orientation.y;
00166     v[5] = pose.orientation.z;
00167     v[6] = pose.orientation.w;
00168     return moveit::py_bindings_tools::listFromDouble(v);
00169   }
00170 
00171   bp::list convertTransformToList(const geometry_msgs::Transform& tr) const
00172   {
00173     std::vector<double> v(7);
00174     v[0] = tr.translation.x;
00175     v[1] = tr.translation.y;
00176     v[2] = tr.translation.z;
00177     v[3] = tr.rotation.x;
00178     v[4] = tr.rotation.y;
00179     v[5] = tr.rotation.z;
00180     v[6] = tr.rotation.w;
00181     return py_bindings_tools::listFromDouble(v);
00182   }
00183 
00184   void convertListToTransform(const bp::list& l, geometry_msgs::Transform& tr) const
00185   {
00186     std::vector<double> v = py_bindings_tools::doubleFromList(l);
00187     tr.translation.x = v[0];
00188     tr.translation.y = v[1];
00189     tr.translation.z = v[2];
00190     tr.rotation.x = v[3];
00191     tr.rotation.y = v[4];
00192     tr.rotation.z = v[5];
00193     tr.rotation.w = v[6];
00194   }
00195 
00196   void convertListToPose(const bp::list& l, geometry_msgs::Pose& p) const
00197   {
00198     std::vector<double> v = py_bindings_tools::doubleFromList(l);
00199     p.position.x = v[0];
00200     p.position.y = v[1];
00201     p.position.z = v[2];
00202     p.orientation.x = v[3];
00203     p.orientation.y = v[4];
00204     p.orientation.z = v[5];
00205     p.orientation.w = v[6];
00206   }
00207 
00208   bp::list getCurrentRPYPython(const std::string& end_effector_link = "")
00209   {
00210     return py_bindings_tools::listFromDouble(getCurrentRPY(end_effector_link));
00211   }
00212 
00213   bp::list getCurrentPosePython(const std::string& end_effector_link = "")
00214   {
00215     geometry_msgs::PoseStamped pose = getCurrentPose(end_effector_link);
00216     return convertPoseToList(pose.pose);
00217   }
00218 
00219   bp::list getRandomPosePython(const std::string& end_effector_link = "")
00220   {
00221     geometry_msgs::PoseStamped pose = getRandomPose(end_effector_link);
00222     return convertPoseToList(pose.pose);
00223   }
00224 
00225   bp::list getKnownConstraintsList() const
00226   {
00227     return py_bindings_tools::listFromString(getKnownConstraints());
00228   }
00229 
00230   bool placePose(const std::string& object_name, const bp::list& pose)
00231   {
00232     geometry_msgs::PoseStamped msg;
00233     convertListToPose(pose, msg.pose);
00234     msg.header.frame_id = getPoseReferenceFrame();
00235     msg.header.stamp = ros::Time::now();
00236     return place(object_name, msg);
00237   }
00238 
00239   bool placeLocation(const std::string& object_name, const std::string& location_str)
00240   {
00241     std::vector<moveit_msgs::PlaceLocation> locations(1);
00242     py_bindings_tools::deserializeMsg(location_str, locations[0]);
00243     return place(object_name, locations);
00244   }
00245 
00246   bool placeAnywhere(const std::string& object_name)
00247   {
00248     return place(object_name);
00249   }
00250 
00251   void convertListToArrayOfPoses(const bp::list& poses, std::vector<geometry_msgs::Pose>& msg)
00252   {
00253     int l = bp::len(poses);
00254     for (int i = 0; i < l; ++i)
00255     {
00256       const bp::list& pose = bp::extract<bp::list>(poses[i]);
00257       std::vector<double> v = py_bindings_tools::doubleFromList(pose);
00258       if (v.size() == 6 || v.size() == 7)
00259       {
00260         Eigen::Affine3d p;
00261         if (v.size() == 6)
00262         {
00263           Eigen::Quaterniond q;
00264           tf::quaternionTFToEigen(tf::createQuaternionFromRPY(v[3], v[4], v[5]), q);
00265           p = Eigen::Affine3d(q);
00266         }
00267         else
00268           p = Eigen::Affine3d(Eigen::Quaterniond(v[6], v[3], v[4], v[5]));
00269         p.translation() = Eigen::Vector3d(v[0], v[1], v[2]);
00270         geometry_msgs::Pose pm;
00271         tf::poseEigenToMsg(p, pm);
00272         msg.push_back(pm);
00273       }
00274       else
00275         ROS_WARN("Incorrect number of values for a pose: %u", (unsigned int)v.size());
00276     }
00277   }
00278 
00279   bp::dict getCurrentStateBoundedPython()
00280   {
00281     robot_state::RobotStatePtr current = getCurrentState();
00282     current->enforceBounds();
00283     moveit_msgs::RobotState rsmv;
00284     robot_state::robotStateToRobotStateMsg(*current, rsmv);
00285     bp::dict output;
00286     for (size_t x = 0; x < rsmv.joint_state.name.size(); ++x)
00287       output[rsmv.joint_state.name[x]] = rsmv.joint_state.position[x];
00288     return output;
00289   }
00290 
00291   void setStartStatePython(const std::string& msg_str)
00292   {
00293     moveit_msgs::RobotState msg;
00294     py_bindings_tools::deserializeMsg(msg_str, msg);
00295     setStartState(msg);
00296   }
00297 
00298   bool setPoseTargetsPython(bp::list& poses, const std::string& end_effector_link = "")
00299   {
00300     std::vector<geometry_msgs::Pose> msg;
00301     convertListToArrayOfPoses(poses, msg);
00302     return setPoseTargets(msg, end_effector_link);
00303   }
00304 
00305   bool setPoseTargetPython(bp::list& pose, const std::string& end_effector_link = "")
00306   {
00307     std::vector<double> v = py_bindings_tools::doubleFromList(pose);
00308     geometry_msgs::Pose msg;
00309     if (v.size() == 6)
00310       tf::quaternionTFToMsg(tf::createQuaternionFromRPY(v[3], v[4], v[5]), msg.orientation);
00311     else if (v.size() == 7)
00312     {
00313       msg.orientation.x = v[3];
00314       msg.orientation.y = v[4];
00315       msg.orientation.z = v[5];
00316       msg.orientation.w = v[6];
00317     }
00318     else
00319     {
00320       ROS_ERROR("Pose description expected to consist of either 6 or 7 values");
00321       return false;
00322     }
00323     msg.position.x = v[0];
00324     msg.position.y = v[1];
00325     msg.position.z = v[2];
00326     return setPoseTarget(msg, end_effector_link);
00327   }
00328 
00329   const char* getEndEffectorLinkCStr() const
00330   {
00331     return getEndEffectorLink().c_str();
00332   }
00333 
00334   const char* getPoseReferenceFrameCStr() const
00335   {
00336     return getPoseReferenceFrame().c_str();
00337   }
00338 
00339   const char* getNameCStr() const
00340   {
00341     return getName().c_str();
00342   }
00343 
00344   bp::dict getNamedTargetValuesPython(const std::string& name)
00345   {
00346     bp::dict output;
00347     std::map<std::string, double> positions = getNamedTargetValues(name);
00348     std::map<std::string, double>::iterator iterator;
00349 
00350     for (iterator = positions.begin(); iterator != positions.end(); iterator++)
00351       output[iterator->first] = iterator->second;
00352     return output;
00353   }
00354 
00355   bp::list getNamedTargetsPython()
00356   {
00357     return py_bindings_tools::listFromString(getNamedTargets());
00358   }
00359 
00360   bool movePython()
00361   {
00362     return move();
00363   }
00364 
00365   bool asyncMovePython()
00366   {
00367     return asyncMove();
00368   }
00369 
00370   bool attachObjectPython(const std::string& object_name, const std::string& link_name, const bp::list& touch_links)
00371   {
00372     return attachObject(object_name, link_name, py_bindings_tools::stringFromList(touch_links));
00373   }
00374 
00375   bool executePython(const std::string& plan_str)
00376   {
00377     MoveGroup::Plan plan;
00378     py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
00379     return execute(plan);
00380   }
00381 
00382   bool asyncExecutePython(const std::string& plan_str)
00383   {
00384     MoveGroup::Plan plan;
00385     py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
00386     return asyncExecute(plan);
00387   }
00388 
00389   std::string getPlanPython()
00390   {
00391     MoveGroup::Plan plan;
00392     MoveGroup::plan(plan);
00393     return py_bindings_tools::serializeMsg(plan.trajectory_);
00394   }
00395 
00396   bp::tuple computeCartesianPathPython(const bp::list& waypoints, double eef_step, double jump_threshold,
00397                                        bool avoid_collisions)
00398   {
00399     std::vector<geometry_msgs::Pose> poses;
00400     convertListToArrayOfPoses(waypoints, poses);
00401     moveit_msgs::RobotTrajectory trajectory;
00402     double fraction = computeCartesianPath(poses, eef_step, jump_threshold, trajectory, avoid_collisions);
00403     return bp::make_tuple(py_bindings_tools::serializeMsg(trajectory), fraction);
00404   }
00405 
00406   int pickGrasp(const std::string& object, const std::string& grasp_str)
00407   {
00408     moveit_msgs::Grasp grasp;
00409     py_bindings_tools::deserializeMsg(grasp_str, grasp);
00410     return pick(object, grasp).val;
00411   }
00412 
00413   int pickGrasps(const std::string& object, const bp::list& grasp_list)
00414   {
00415     int l = bp::len(grasp_list);
00416     std::vector<moveit_msgs::Grasp> grasps(l);
00417     for (int i = 0; i < l; ++i)
00418       py_bindings_tools::deserializeMsg(bp::extract<std::string>(grasp_list[i]), grasps[i]);
00419     return pick(object, grasps).val;
00420   }
00421 
00422   void setPathConstraintsFromMsg(const std::string& constraints_str)
00423   {
00424     moveit_msgs::Constraints constraints_msg;
00425     py_bindings_tools::deserializeMsg(constraints_str, constraints_msg);
00426     setPathConstraints(constraints_msg);
00427   }
00428 
00429   std::string getPathConstraintsPython()
00430   {
00431     moveit_msgs::Constraints constraints_msg(getPathConstraints());
00432     std::string constraints_str = py_bindings_tools::serializeMsg(constraints_msg);
00433     return constraints_str;
00434   }
00435 
00436   std::string retimeTrajectory(const std::string& ref_state_str, const std::string& traj_str,
00437                                double velocity_scaling_factor)
00438   {
00439     // Convert reference state message to object
00440     moveit_msgs::RobotState ref_state_msg;
00441     py_bindings_tools::deserializeMsg(ref_state_str, ref_state_msg);
00442     moveit::core::RobotState ref_state_obj(getRobotModel());
00443     if (moveit::core::robotStateMsgToRobotState(ref_state_msg, ref_state_obj, true))
00444     {
00445       // Convert trajectory message to object
00446       moveit_msgs::RobotTrajectory traj_msg;
00447       py_bindings_tools::deserializeMsg(traj_str, traj_msg);
00448       robot_trajectory::RobotTrajectory traj_obj(getRobotModel(), getName());
00449       traj_obj.setRobotTrajectoryMsg(ref_state_obj, traj_msg);
00450 
00451       // Do the actual retiming
00452       trajectory_processing::IterativeParabolicTimeParameterization time_param;
00453       time_param.computeTimeStamps(traj_obj, velocity_scaling_factor);
00454 
00455       // Convert the retimed trajectory back into a message
00456       traj_obj.getRobotTrajectoryMsg(traj_msg);
00457       std::string traj_str = py_bindings_tools::serializeMsg(traj_msg);
00458 
00459       // Return it.
00460       return traj_str;
00461     }
00462     else
00463     {
00464       ROS_ERROR("Unable to convert RobotState message to RobotState instance.");
00465       return "";
00466     }
00467   }
00468 };
00469 
00470 static void wrap_move_group_interface()
00471 {
00472   bp::class_<MoveGroupWrapper> MoveGroupClass("MoveGroup", bp::init<std::string, std::string>());
00473 
00474   MoveGroupClass.def("async_move", &MoveGroupWrapper::asyncMovePython);
00475   MoveGroupClass.def("move", &MoveGroupWrapper::movePython);
00476   MoveGroupClass.def("execute", &MoveGroupWrapper::executePython);
00477   MoveGroupClass.def("async_execute", &MoveGroupWrapper::asyncExecutePython);
00478   moveit::planning_interface::MoveItErrorCode (MoveGroupWrapper::*pick_1)(const std::string&) = &MoveGroupWrapper::pick;
00479   MoveGroupClass.def("pick", pick_1);
00480   MoveGroupClass.def("pick", &MoveGroupWrapper::pickGrasp);
00481   MoveGroupClass.def("pick", &MoveGroupWrapper::pickGrasps);
00482   MoveGroupClass.def("place", &MoveGroupWrapper::placePose);
00483   MoveGroupClass.def("place", &MoveGroupWrapper::placeLocation);
00484   MoveGroupClass.def("place", &MoveGroupWrapper::placeAnywhere);
00485   MoveGroupClass.def("stop", &MoveGroupWrapper::stop);
00486 
00487   MoveGroupClass.def("get_name", &MoveGroupWrapper::getNameCStr);
00488   MoveGroupClass.def("get_planning_frame", &MoveGroupWrapper::getPlanningFrameCStr);
00489 
00490   MoveGroupClass.def("get_active_joints", &MoveGroupWrapper::getActiveJointsList);
00491   MoveGroupClass.def("get_joints", &MoveGroupWrapper::getJointsList);
00492   MoveGroupClass.def("get_variable_count", &MoveGroupWrapper::getVariableCount);
00493   MoveGroupClass.def("allow_looking", &MoveGroupWrapper::allowLooking);
00494   MoveGroupClass.def("allow_replanning", &MoveGroupWrapper::allowReplanning);
00495 
00496   MoveGroupClass.def("set_pose_reference_frame", &MoveGroupWrapper::setPoseReferenceFrame);
00497 
00498   MoveGroupClass.def("set_pose_reference_frame", &MoveGroupWrapper::setPoseReferenceFrame);
00499   MoveGroupClass.def("set_end_effector_link", &MoveGroupWrapper::setEndEffectorLink);
00500   MoveGroupClass.def("get_end_effector_link", &MoveGroupWrapper::getEndEffectorLinkCStr);
00501   MoveGroupClass.def("get_pose_reference_frame", &MoveGroupWrapper::getPoseReferenceFrameCStr);
00502 
00503   MoveGroupClass.def("set_pose_target", &MoveGroupWrapper::setPoseTargetPython);
00504 
00505   MoveGroupClass.def("set_pose_targets", &MoveGroupWrapper::setPoseTargetsPython);
00506 
00507   MoveGroupClass.def("set_position_target", &MoveGroupWrapper::setPositionTarget);
00508   MoveGroupClass.def("set_rpy_target", &MoveGroupWrapper::setRPYTarget);
00509   MoveGroupClass.def("set_orientation_target", &MoveGroupWrapper::setOrientationTarget);
00510 
00511   MoveGroupClass.def("get_current_pose", &MoveGroupWrapper::getCurrentPosePython);
00512   MoveGroupClass.def("get_current_rpy", &MoveGroupWrapper::getCurrentRPYPython);
00513 
00514   MoveGroupClass.def("get_random_pose", &MoveGroupWrapper::getRandomPosePython);
00515 
00516   MoveGroupClass.def("clear_pose_target", &MoveGroupWrapper::clearPoseTarget);
00517   MoveGroupClass.def("clear_pose_targets", &MoveGroupWrapper::clearPoseTargets);
00518 
00519   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPythonIterable);
00520   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPythonDict);
00521 
00522   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPerJointPythonList);
00523   bool (MoveGroupWrapper::*setJointValueTarget_4)(const std::string&, double) = &MoveGroupWrapper::setJointValueTarget;
00524   MoveGroupClass.def("set_joint_value_target", setJointValueTarget_4);
00525 
00526   MoveGroupClass.def("set_joint_value_target_from_pose", &MoveGroupWrapper::setJointValueTargetFromPosePython);
00527   MoveGroupClass.def("set_joint_value_target_from_pose_stamped",
00528                      &MoveGroupWrapper::setJointValueTargetFromPoseStampedPython);
00529   MoveGroupClass.def("set_joint_value_target_from_joint_state_message",
00530                      &MoveGroupWrapper::setJointValueTargetFromJointStatePython);
00531 
00532   MoveGroupClass.def("get_joint_value_target", &MoveGroupWrapper::getJointValueTargetPythonList);
00533 
00534   MoveGroupClass.def("set_named_target", &MoveGroupWrapper::setNamedTarget);
00535   MoveGroupClass.def("set_random_target", &MoveGroupWrapper::setRandomTarget);
00536 
00537   void (MoveGroupWrapper::*rememberJointValues_2)(const std::string&) = &MoveGroupWrapper::rememberJointValues;
00538   MoveGroupClass.def("remember_joint_values", rememberJointValues_2);
00539 
00540   MoveGroupClass.def("remember_joint_values", &MoveGroupWrapper::rememberJointValuesFromPythonList);
00541 
00542   MoveGroupClass.def("start_state_monitor", &MoveGroupWrapper::startStateMonitor);
00543   MoveGroupClass.def("get_current_joint_values", &MoveGroupWrapper::getCurrentJointValuesList);
00544   MoveGroupClass.def("get_random_joint_values", &MoveGroupWrapper::getRandomJointValuesList);
00545   MoveGroupClass.def("get_remembered_joint_values", &MoveGroupWrapper::getRememberedJointValuesPython);
00546 
00547   MoveGroupClass.def("forget_joint_values", &MoveGroupWrapper::forgetJointValues);
00548 
00549   MoveGroupClass.def("get_goal_joint_tolerance", &MoveGroupWrapper::getGoalJointTolerance);
00550   MoveGroupClass.def("get_goal_position_tolerance", &MoveGroupWrapper::getGoalPositionTolerance);
00551   MoveGroupClass.def("get_goal_orientation_tolerance", &MoveGroupWrapper::getGoalOrientationTolerance);
00552 
00553   MoveGroupClass.def("set_goal_joint_tolerance", &MoveGroupWrapper::setGoalJointTolerance);
00554   MoveGroupClass.def("set_goal_position_tolerance", &MoveGroupWrapper::setGoalPositionTolerance);
00555   MoveGroupClass.def("set_goal_orientation_tolerance", &MoveGroupWrapper::setGoalOrientationTolerance);
00556   MoveGroupClass.def("set_goal_tolerance", &MoveGroupWrapper::setGoalTolerance);
00557 
00558   MoveGroupClass.def("set_start_state_to_current_state", &MoveGroupWrapper::setStartStateToCurrentState);
00559   MoveGroupClass.def("set_start_state", &MoveGroupWrapper::setStartStatePython);
00560 
00561   bool (MoveGroupWrapper::*setPathConstraints_1)(const std::string&) = &MoveGroupWrapper::setPathConstraints;
00562   MoveGroupClass.def("set_path_constraints", setPathConstraints_1);
00563   MoveGroupClass.def("set_path_constraints_from_msg", &MoveGroupWrapper::setPathConstraintsFromMsg);
00564   MoveGroupClass.def("get_path_constraints", &MoveGroupWrapper::getPathConstraintsPython);
00565   MoveGroupClass.def("clear_path_constraints", &MoveGroupWrapper::clearPathConstraints);
00566   MoveGroupClass.def("get_known_constraints", &MoveGroupWrapper::getKnownConstraintsList);
00567   MoveGroupClass.def("set_constraints_database", &MoveGroupWrapper::setConstraintsDatabase);
00568   MoveGroupClass.def("set_workspace", &MoveGroupWrapper::setWorkspace);
00569   MoveGroupClass.def("set_planning_time", &MoveGroupWrapper::setPlanningTime);
00570   MoveGroupClass.def("get_planning_time", &MoveGroupWrapper::getPlanningTime);
00571   MoveGroupClass.def("set_max_acceleration_scaling_factor", &MoveGroupWrapper::setMaxAccelerationScalingFactor);
00572   MoveGroupClass.def("set_max_velocity_scaling_factor", &MoveGroupWrapper::setMaxVelocityScalingFactor);
00573   MoveGroupClass.def("set_planner_id", &MoveGroupWrapper::setPlannerId);
00574   MoveGroupClass.def("set_num_planning_attempts", &MoveGroupWrapper::setNumPlanningAttempts);
00575   MoveGroupClass.def("compute_plan", &MoveGroupWrapper::getPlanPython);
00576   MoveGroupClass.def("compute_cartesian_path", &MoveGroupWrapper::computeCartesianPathPython);
00577   MoveGroupClass.def("set_support_surface_name", &MoveGroupWrapper::setSupportSurfaceName);
00578   MoveGroupClass.def("attach_object", &MoveGroupWrapper::attachObjectPython);
00579   MoveGroupClass.def("detach_object", &MoveGroupWrapper::detachObject);
00580   MoveGroupClass.def("retime_trajectory", &MoveGroupWrapper::retimeTrajectory);
00581   MoveGroupClass.def("get_named_targets", &MoveGroupWrapper::getNamedTargetsPython);
00582   MoveGroupClass.def("get_named_target_values", &MoveGroupWrapper::getNamedTargetValuesPython);
00583   MoveGroupClass.def("get_current_state_bounded", &MoveGroupWrapper::getCurrentStateBoundedPython);
00584 }
00585 }
00586 }
00587 
00588 BOOST_PYTHON_MODULE(_moveit_move_group_interface)
00589 {
00590   using namespace moveit::planning_interface;
00591   wrap_move_group_interface();
00592 }
00593 


planning_interface
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:53