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


planning_interface
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:22:06