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 <eigen_conversions/eigen_msg.h>
00042 #include <tf_conversions/tf_eigen.h>
00043 
00044 #include <boost/python.hpp>
00045 #include <boost/shared_ptr.hpp>
00046 #include <Python.h>
00047 
00050 namespace bp = boost::python;
00051 
00052 namespace moveit
00053 {
00054 namespace planning_interface
00055 {
00056 
00057 class MoveGroupWrapper : protected py_bindings_tools::ROScppInitializer,
00058                          public MoveGroup
00059 {
00060 public:
00061 
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::Duration(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 setJointValueTargetPythonList(bp::list &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   void rememberJointValuesFromPythonList(const std::string &string, bp::list &values)
00111   {
00112     rememberJointValues(string, py_bindings_tools::doubleFromList(values));
00113   }
00114 
00115   const char* getPlanningFrameCStr() const
00116   {
00117     return getPlanningFrame().c_str();
00118   }
00119 
00120   bp::list getActiveJointsList() const
00121   {
00122     return py_bindings_tools::listFromString(getActiveJoints());
00123   }
00124 
00125   bp::list getJointsList() const
00126   {
00127     return py_bindings_tools::listFromString(getJoints());
00128   }
00129 
00130   bp::list getCurrentJointValuesList()
00131   {
00132     return py_bindings_tools::listFromDouble(getCurrentJointValues());
00133   }
00134 
00135   bp::list getRandomJointValuesList()
00136   {
00137     return py_bindings_tools::listFromDouble(getRandomJointValues());
00138   }
00139 
00140   bp::dict getRememberedJointValuesPython() const
00141   {
00142     const std::map<std::string, std::vector<double> > &rv = getRememberedJointValues();
00143     bp::dict d;
00144     for (std::map<std::string, std::vector<double> >::const_iterator it = rv.begin() ; it != rv.end() ; ++it)
00145       d[it->first] = py_bindings_tools::listFromDouble(it->second);
00146     return d;
00147   }
00148 
00149   bp::list convertPoseToList(const geometry_msgs::Pose &pose) const
00150   {
00151     std::vector<double> v(7);
00152     v[0] = pose.position.x;
00153     v[1] = pose.position.y;
00154     v[2] = pose.position.z;
00155     v[3] = pose.orientation.x;
00156     v[4] = pose.orientation.y;
00157     v[5] = pose.orientation.z;
00158     v[6] = pose.orientation.w;
00159     return moveit::py_bindings_tools::listFromDouble(v);
00160   }
00161 
00162   bp::list convertTransformToList(const geometry_msgs::Transform &tr) const
00163   {
00164     std::vector<double> v(7);
00165     v[0] = tr.translation.x;
00166     v[1] = tr.translation.y;
00167     v[2] = tr.translation.z;
00168     v[3] = tr.rotation.x;
00169     v[4] = tr.rotation.y;
00170     v[5] = tr.rotation.z;
00171     v[6] = tr.rotation.w;
00172     return py_bindings_tools::listFromDouble(v);
00173   }
00174 
00175   void convertListToTransform(const bp::list &l, geometry_msgs::Transform &tr) const
00176   {
00177     std::vector<double> v = py_bindings_tools::doubleFromList(l);
00178     tr.translation.x =  v[0];
00179     tr.translation.y = v[1];
00180     tr.translation.z = v[2];
00181     tr.rotation.x = v[3];
00182     tr.rotation.y = v[4];
00183     tr.rotation.z = v[5];
00184     tr.rotation.w = v[6];
00185   }
00186 
00187   void convertListToPose(const bp::list &l, geometry_msgs::Pose &p) const
00188   {
00189     std::vector<double> v = py_bindings_tools::doubleFromList(l);
00190     p.position.x =  v[0];
00191     p.position.y = v[1];
00192     p.position.z = v[2];
00193     p.orientation.x = v[3];
00194     p.orientation.y = v[4];
00195     p.orientation.z = v[5];
00196     p.orientation.w = v[6];
00197   }
00198 
00199   bp::list getCurrentRPYPython(const std::string &end_effector_link = "")
00200   {
00201     return py_bindings_tools::listFromDouble(getCurrentRPY(end_effector_link));
00202   }
00203 
00204   bp::list getCurrentPosePython(const std::string &end_effector_link = "")
00205   {
00206     geometry_msgs::PoseStamped pose = getCurrentPose(end_effector_link);
00207     return convertPoseToList(pose.pose);
00208   }
00209 
00210   bp::list getRandomPosePython(const std::string &end_effector_link = "")
00211   {
00212     geometry_msgs::PoseStamped pose = getRandomPose(end_effector_link);
00213     return convertPoseToList(pose.pose);
00214   }
00215 
00216   bp::list getKnownConstraintsList() const
00217   {
00218     return py_bindings_tools::listFromString(getKnownConstraints());
00219   }
00220 
00221   bool placePose(const std::string &object_name, const bp::list &pose)
00222   {
00223     geometry_msgs::PoseStamped msg;
00224     convertListToPose(pose, msg.pose);
00225     msg.header.frame_id = getPoseReferenceFrame();
00226     msg.header.stamp = ros::Time::now();
00227     return place(object_name, msg);
00228   }
00229 
00230   bool placeLocation(const std::string &object_name, const std::string &location_str)
00231   {
00232     std::vector<moveit_msgs::PlaceLocation> locations(1);
00233     py_bindings_tools::deserializeMsg(location_str, locations[0]);
00234     return place(object_name, locations);
00235   }
00236 
00237   bool placeAnywhere(const std::string &object_name)
00238   {
00239     return place(object_name);
00240   }
00241 
00242   void convertListToArrayOfPoses(const bp::list &poses, std::vector<geometry_msgs::Pose> &msg)
00243   {
00244     int l = bp::len(poses);
00245     for (int i = 0; i < l ; ++i)
00246     {
00247       const bp::list &pose = bp::extract<bp::list>(poses[i]);
00248       std::vector<double> v = py_bindings_tools::doubleFromList(pose);
00249       if (v.size() == 6 || v.size() == 7)
00250       {
00251         Eigen::Affine3d p;
00252         if (v.size() == 6)
00253         {
00254           Eigen::Quaterniond q;
00255           tf::quaternionTFToEigen(tf::createQuaternionFromRPY(v[3], v[4], v[5]), q);
00256           p = Eigen::Affine3d(q);
00257         }
00258         else
00259           p = Eigen::Affine3d(Eigen::Quaterniond(v[6], v[3], v[4], v[5]));
00260         p.translation() = Eigen::Vector3d(v[0], v[1], v[2]);
00261         geometry_msgs::Pose pm;
00262         tf::poseEigenToMsg(p, pm);
00263         msg.push_back(pm);
00264       }
00265       else
00266         ROS_WARN("Incorrect number of values for a pose: %u", (unsigned int)v.size());
00267     }
00268   }
00269 
00270   void setStartStatePython(const std::string &msg_str)
00271   {
00272     moveit_msgs::RobotState msg;
00273     py_bindings_tools::deserializeMsg(msg_str, msg);
00274     setStartState(msg);
00275   }
00276 
00277   bool setPoseTargetsPython(bp::list &poses, const std::string &end_effector_link = "")
00278   {
00279     std::vector<geometry_msgs::Pose> msg;
00280     convertListToArrayOfPoses(poses, msg);
00281     return setPoseTargets(msg, end_effector_link);
00282   }
00283 
00284   bool setPoseTargetPython(bp::list &pose, const std::string &end_effector_link = "")
00285   {
00286     std::vector<double> v = py_bindings_tools::doubleFromList(pose);
00287     geometry_msgs::Pose msg;
00288     if (v.size() == 6)
00289       tf::quaternionTFToMsg(tf::createQuaternionFromRPY(v[3], v[4], v[5]), msg.orientation);
00290     else
00291       if (v.size() == 7)
00292       {
00293         msg.orientation.x = v[3];
00294         msg.orientation.y = v[4];
00295         msg.orientation.z = v[5];
00296         msg.orientation.w = v[6];
00297       }
00298       else
00299       {
00300         ROS_ERROR("Pose description expected to consist of either 6 or 7 values");
00301         return false;
00302       }
00303     msg.position.x = v[0];
00304     msg.position.y = v[1];
00305     msg.position.z = v[2];
00306     return setPoseTarget(msg, end_effector_link);
00307   }
00308 
00309   const char* getEndEffectorLinkCStr() const
00310   {
00311     return getEndEffectorLink().c_str();
00312   }
00313 
00314   const char* getPoseReferenceFrameCStr() const
00315   {
00316     return getPoseReferenceFrame().c_str();
00317   }
00318 
00319   const char* getNameCStr() const
00320   {
00321     return getName().c_str();
00322   }
00323 
00324   bool movePython()
00325   {
00326     return move();
00327   }
00328 
00329   bool asyncMovePython()
00330   {
00331     return asyncMove();
00332   }
00333 
00334   bool attachObjectPython(const std::string &object_name, const std::string &link_name, const bp::list &touch_links)
00335   {
00336     return attachObject(object_name, link_name, py_bindings_tools::stringFromList(touch_links));
00337   }
00338 
00339   bool executePython(const std::string &plan_str)
00340   {
00341     MoveGroup::Plan plan;
00342     py_bindings_tools::deserializeMsg(plan_str, plan.trajectory_);
00343     return execute(plan);
00344   }
00345 
00346   std::string getPlanPython()
00347   {
00348     MoveGroup::Plan plan;
00349     MoveGroup::plan(plan);
00350     return py_bindings_tools::serializeMsg(plan.trajectory_);
00351   }
00352 
00353   bp::tuple computeCartesianPathPython(const bp::list &waypoints, double eef_step, double jump_threshold, bool avoid_collisions)
00354   {
00355     std::vector<geometry_msgs::Pose> poses;
00356     convertListToArrayOfPoses(waypoints, poses);
00357     moveit_msgs::RobotTrajectory trajectory;
00358     double fraction = computeCartesianPath(poses, eef_step, jump_threshold, trajectory, avoid_collisions);
00359     return bp::make_tuple(py_bindings_tools::serializeMsg(trajectory), fraction);
00360   }
00361 
00362   int pickGrasp(const std::string &object, const std::string &grasp_str)
00363   {
00364     moveit_msgs::Grasp grasp;
00365     py_bindings_tools::deserializeMsg(grasp_str, grasp);
00366     return pick(object, grasp).val;
00367   }
00368 
00369   int pickGrasps(const std::string &object, const bp::list &grasp_list)
00370   {
00371     int l = bp::len(grasp_list);
00372     std::vector<moveit_msgs::Grasp> grasps(l);
00373     for (int i = 0; i < l ; ++i)
00374       py_bindings_tools::deserializeMsg(bp::extract<std::string>(grasp_list[i]), grasps[i]);
00375     return pick(object, grasps).val;
00376   }
00377 
00378   void setPathConstraintsFromMsg(const std::string &constraints_str)
00379   {
00380       moveit_msgs::Constraints constraints_msg;
00381       py_bindings_tools::deserializeMsg(constraints_str,constraints_msg);
00382       setPathConstraints(constraints_msg);
00383   }
00384 
00385   std::string getPathConstraintsPython()
00386   {
00387      moveit_msgs::Constraints constraints_msg(getPathConstraints());
00388      std::string constraints_str = py_bindings_tools::serializeMsg(constraints_msg);
00389      return constraints_str;
00390   }
00391 
00392 };
00393 
00394 static void wrap_move_group_interface()
00395 {
00396   bp::class_<MoveGroupWrapper> MoveGroupClass("MoveGroup", bp::init<std::string, std::string>());
00397 
00398   MoveGroupClass.def("async_move", &MoveGroupWrapper::asyncMovePython);
00399   MoveGroupClass.def("move", &MoveGroupWrapper::movePython);
00400   MoveGroupClass.def("execute", &MoveGroupWrapper::executePython);
00401   moveit::planning_interface::MoveItErrorCode (MoveGroupWrapper::*pick_1)(const std::string&) = &MoveGroupWrapper::pick;
00402   MoveGroupClass.def("pick", pick_1);
00403   MoveGroupClass.def("pick", &MoveGroupWrapper::pickGrasp);
00404   MoveGroupClass.def("pick", &MoveGroupWrapper::pickGrasps);
00405   MoveGroupClass.def("place", &MoveGroupWrapper::placePose);
00406   MoveGroupClass.def("place", &MoveGroupWrapper::placeLocation);
00407   MoveGroupClass.def("place", &MoveGroupWrapper::placeAnywhere);
00408   MoveGroupClass.def("stop", &MoveGroupWrapper::stop);
00409 
00410   MoveGroupClass.def("get_name", &MoveGroupWrapper::getNameCStr);
00411   MoveGroupClass.def("get_planning_frame", &MoveGroupWrapper::getPlanningFrameCStr);
00412 
00413   MoveGroupClass.def("get_active_joints", &MoveGroupWrapper::getActiveJointsList);
00414   MoveGroupClass.def("get_joints", &MoveGroupWrapper::getJointsList);
00415   MoveGroupClass.def("get_variable_count", &MoveGroupWrapper::getVariableCount);
00416   MoveGroupClass.def("allow_looking", &MoveGroupWrapper::allowLooking);
00417   MoveGroupClass.def("allow_replanning", &MoveGroupWrapper::allowReplanning);
00418 
00419   MoveGroupClass.def("set_pose_reference_frame", &MoveGroupWrapper::setPoseReferenceFrame);
00420 
00421   MoveGroupClass.def("set_pose_reference_frame", &MoveGroupWrapper::setPoseReferenceFrame);
00422   MoveGroupClass.def("set_end_effector_link", &MoveGroupWrapper::setEndEffectorLink);
00423   MoveGroupClass.def("get_end_effector_link", &MoveGroupWrapper::getEndEffectorLinkCStr);
00424   MoveGroupClass.def("get_pose_reference_frame", &MoveGroupWrapper::getPoseReferenceFrameCStr);
00425 
00426   MoveGroupClass.def("set_pose_target", &MoveGroupWrapper::setPoseTargetPython);
00427 
00428   MoveGroupClass.def("set_pose_targets", &MoveGroupWrapper::setPoseTargetsPython);
00429 
00430   MoveGroupClass.def("set_position_target", &MoveGroupWrapper::setPositionTarget);
00431   MoveGroupClass.def("set_rpy_target", &MoveGroupWrapper::setRPYTarget);
00432   MoveGroupClass.def("set_orientation_target", &MoveGroupWrapper::setOrientationTarget);
00433 
00434   MoveGroupClass.def("get_current_pose", &MoveGroupWrapper::getCurrentPosePython);
00435   MoveGroupClass.def("get_current_rpy", &MoveGroupWrapper::getCurrentRPYPython);
00436 
00437   MoveGroupClass.def("get_random_pose", &MoveGroupWrapper::getRandomPosePython);
00438 
00439   MoveGroupClass.def("clear_pose_target", &MoveGroupWrapper::clearPoseTarget);
00440   MoveGroupClass.def("clear_pose_targets", &MoveGroupWrapper::clearPoseTargets);
00441 
00442   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPythonList);
00443   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPythonDict);
00444 
00445   MoveGroupClass.def("set_joint_value_target", &MoveGroupWrapper::setJointValueTargetPerJointPythonList);
00446   bool (MoveGroupWrapper::*setJointValueTarget_4)(const std::string&, double) = &MoveGroupWrapper::setJointValueTarget;
00447   MoveGroupClass.def("set_joint_value_target", setJointValueTarget_4);
00448 
00449   MoveGroupClass.def("set_joint_value_target_from_pose", &MoveGroupWrapper::setJointValueTargetFromPosePython);
00450   MoveGroupClass.def("set_joint_value_target_from_pose_stamped", &MoveGroupWrapper::setJointValueTargetFromPoseStampedPython);
00451   MoveGroupClass.def("set_joint_value_target_from_joint_state_message", &MoveGroupWrapper::setJointValueTargetFromJointStatePython);
00452 
00453   MoveGroupClass.def("set_named_target", &MoveGroupWrapper::setNamedTarget);
00454   MoveGroupClass.def("set_random_target", &MoveGroupWrapper::setRandomTarget);
00455 
00456   void (MoveGroupWrapper::*rememberJointValues_2)(const std::string&) = &MoveGroupWrapper::rememberJointValues;
00457   MoveGroupClass.def("remember_joint_values", rememberJointValues_2);
00458 
00459   MoveGroupClass.def("remember_joint_values",  &MoveGroupWrapper::rememberJointValuesFromPythonList);
00460 
00461   MoveGroupClass.def("start_state_monitor",  &MoveGroupWrapper::startStateMonitor);
00462   MoveGroupClass.def("get_current_joint_values",  &MoveGroupWrapper::getCurrentJointValuesList);
00463   MoveGroupClass.def("get_random_joint_values",  &MoveGroupWrapper::getRandomJointValuesList);
00464   MoveGroupClass.def("get_remembered_joint_values",  &MoveGroupWrapper::getRememberedJointValuesPython);
00465 
00466   MoveGroupClass.def("forget_joint_values", &MoveGroupWrapper::forgetJointValues);
00467 
00468   MoveGroupClass.def("get_goal_joint_tolerance", &MoveGroupWrapper::getGoalJointTolerance);
00469   MoveGroupClass.def("get_goal_position_tolerance", &MoveGroupWrapper::getGoalPositionTolerance);
00470   MoveGroupClass.def("get_goal_orientation_tolerance", &MoveGroupWrapper::getGoalOrientationTolerance);
00471 
00472   MoveGroupClass.def("set_goal_joint_tolerance", &MoveGroupWrapper::setGoalJointTolerance);
00473   MoveGroupClass.def("set_goal_position_tolerance", &MoveGroupWrapper::setGoalPositionTolerance);
00474   MoveGroupClass.def("set_goal_orientation_tolerance", &MoveGroupWrapper::setGoalOrientationTolerance);
00475   MoveGroupClass.def("set_goal_tolerance", &MoveGroupWrapper::setGoalTolerance);
00476 
00477   MoveGroupClass.def("set_start_state_to_current_state", &MoveGroupWrapper::setStartStateToCurrentState);
00478   MoveGroupClass.def("set_start_state", &MoveGroupWrapper::setStartStatePython);
00479 
00480   bool (MoveGroupWrapper::*setPathConstraints_1)(const std::string&) = &MoveGroupWrapper::setPathConstraints;
00481   MoveGroupClass.def("set_path_constraints", setPathConstraints_1);
00482   MoveGroupClass.def("set_path_constraints_from_msg", &MoveGroupWrapper::setPathConstraintsFromMsg);
00483   MoveGroupClass.def("get_path_constraints", &MoveGroupWrapper::getPathConstraintsPython);
00484   MoveGroupClass.def("clear_path_constraints", &MoveGroupWrapper::clearPathConstraints);
00485   MoveGroupClass.def("get_known_constraints", &MoveGroupWrapper::getKnownConstraintsList);
00486   MoveGroupClass.def("set_constraints_database", &MoveGroupWrapper::setConstraintsDatabase);
00487   MoveGroupClass.def("set_workspace", &MoveGroupWrapper::setWorkspace);
00488   MoveGroupClass.def("set_planning_time", &MoveGroupWrapper::setPlanningTime);
00489   MoveGroupClass.def("get_planning_time", &MoveGroupWrapper::getPlanningTime);
00490   MoveGroupClass.def("set_planner_id", &MoveGroupWrapper::setPlannerId);
00491   MoveGroupClass.def("compute_plan", &MoveGroupWrapper::getPlanPython);
00492   MoveGroupClass.def("compute_cartesian_path", &MoveGroupWrapper::computeCartesianPathPython);
00493   MoveGroupClass.def("set_support_surface_name", &MoveGroupWrapper::setSupportSurfaceName);
00494   MoveGroupClass.def("attach_object", &MoveGroupWrapper::attachObjectPython);
00495   MoveGroupClass.def("detach_object", &MoveGroupWrapper::detachObject);
00496 }
00497 
00498 }
00499 }
00500 
00501 BOOST_PYTHON_MODULE(_moveit_move_group_interface)
00502 {
00503   using namespace moveit::planning_interface;
00504   wrap_move_group_interface();
00505 }
00506 


planning_interface
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:44:13