wrap_python_planning_scene_interface.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, 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/planning_scene_interface/planning_scene_interface.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 
00042 #include <boost/function.hpp>
00043 #include <boost/python.hpp>
00044 #include <Python.h>
00045 
00048 namespace bp = boost::python;
00049 
00050 namespace moveit
00051 {
00052 namespace planning_interface
00053 {
00054 class PlanningSceneInterfaceWrapper : protected py_bindings_tools::ROScppInitializer, public PlanningSceneInterface
00055 {
00056 public:
00057   // ROSInitializer is constructed first, and ensures ros::init() was called, if needed
00058   PlanningSceneInterfaceWrapper() : py_bindings_tools::ROScppInitializer(), PlanningSceneInterface()
00059   {
00060   }
00061 
00062   bp::list getKnownObjectNamesPython(bool with_type = false)
00063   {
00064     return py_bindings_tools::listFromString(getKnownObjectNames(with_type));
00065   }
00066 
00067   bp::list getKnownObjectNamesInROIPython(double minx, double miny, double minz, double maxx, double maxy, double maxz,
00068                                           bool with_type = false)
00069   {
00070     return py_bindings_tools::listFromString(getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type));
00071   }
00072 
00073   bp::dict getObjectPosesPython(bp::list object_ids)
00074   {
00075     std::map<std::string, geometry_msgs::Pose> ops = getObjectPoses(py_bindings_tools::stringFromList(object_ids));
00076     std::map<std::string, std::string> ser_ops;
00077     for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = ops.begin(); it != ops.end(); ++it)
00078       ser_ops[it->first] = py_bindings_tools::serializeMsg(it->second);
00079 
00080     return py_bindings_tools::dictFromType(ser_ops);
00081   }
00082 
00083   bp::dict getObjectsPython(bp::list object_ids)
00084   {
00085     std::map<std::string, moveit_msgs::CollisionObject> objs =
00086         getObjects(py_bindings_tools::stringFromList(object_ids));
00087     std::map<std::string, std::string> ser_objs;
00088     for (std::map<std::string, moveit_msgs::CollisionObject>::const_iterator it = objs.begin(); it != objs.end(); ++it)
00089       ser_objs[it->first] = py_bindings_tools::serializeMsg(it->second);
00090 
00091     return py_bindings_tools::dictFromType(ser_objs);
00092   }
00093 
00094   bp::dict getAttachedObjectsPython(const bp::list& object_ids)
00095   {
00096     std::map<std::string, moveit_msgs::AttachedCollisionObject> aobjs =
00097         getAttachedObjects(py_bindings_tools::stringFromList(object_ids));
00098     std::map<std::string, std::string> ser_aobjs;
00099     for (std::map<std::string, moveit_msgs::AttachedCollisionObject>::const_iterator it = aobjs.begin();
00100          it != aobjs.end(); ++it)
00101       ser_aobjs[it->first] = py_bindings_tools::serializeMsg(it->second);
00102 
00103     return py_bindings_tools::dictFromType(ser_aobjs);
00104   }
00105 };
00106 
00107 static void wrap_planning_scene_interface()
00108 {
00109   bp::class_<PlanningSceneInterfaceWrapper> PlanningSceneClass("PlanningSceneInterface");
00110 
00111   PlanningSceneClass.def("get_known_object_names", &PlanningSceneInterfaceWrapper::getKnownObjectNamesPython);
00112   PlanningSceneClass.def("get_known_object_names_in_roi",
00113                          &PlanningSceneInterfaceWrapper::getKnownObjectNamesInROIPython);
00114   PlanningSceneClass.def("get_object_poses", &PlanningSceneInterfaceWrapper::getObjectPosesPython);
00115   PlanningSceneClass.def("get_objects", &PlanningSceneInterfaceWrapper::getObjectsPython);
00116   PlanningSceneClass.def("get_attached_objects", &PlanningSceneInterfaceWrapper::getAttachedObjectsPython);
00117 }
00118 }
00119 }
00120 
00121 BOOST_PYTHON_MODULE(_moveit_planning_scene_interface)
00122 {
00123   using namespace moveit::planning_interface;
00124   wrap_planning_scene_interface();
00125 }
00126 


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