42 #include <boost/function.hpp> 
   43 #include <boost/python.hpp> 
   54 class PlanningSceneInterfaceWrapper : 
protected py_bindings_tools::ROScppInitializer, 
public PlanningSceneInterface
 
   58   PlanningSceneInterfaceWrapper(
const std::string& ns = 
"")
 
   59     : py_bindings_tools::ROScppInitializer(), PlanningSceneInterface(ns)
 
   63   bp::list getKnownObjectNamesPython(
bool with_type = 
false)
 
   68   bp::list getKnownObjectNamesInROIPython(
double minx, 
double miny, 
double minz, 
double maxx, 
double maxy, 
double maxz,
 
   69                                           bool with_type = 
false)
 
   74   bp::dict getObjectPosesPython(
const bp::list& object_ids)
 
   77     std::map<std::string, py_bindings_tools::ByteString> ser_ops;
 
   78     for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = ops.begin(); it != ops.end(); ++it)
 
   84   bp::dict getObjectsPython(
const bp::list& object_ids)
 
   86     std::map<std::string, moveit_msgs::CollisionObject> objs =
 
   88     std::map<std::string, py_bindings_tools::ByteString> ser_objs;
 
   89     for (std::map<std::string, moveit_msgs::CollisionObject>::const_iterator it = objs.begin(); it != objs.end(); ++it)
 
   95   bp::dict getAttachedObjectsPython(
const bp::list& object_ids)
 
   97     std::map<std::string, moveit_msgs::AttachedCollisionObject> aobjs =
 
   99     std::map<std::string, py_bindings_tools::ByteString> ser_aobjs;
 
  100     for (std::map<std::string, moveit_msgs::AttachedCollisionObject>::const_iterator it = aobjs.begin();
 
  101          it != aobjs.end(); ++it)
 
  107   py_bindings_tools::ByteString getPlanningScenePython(
const uint32_t components)
 
  109     moveit_msgs::PlanningScene msg = getPlanningSceneMsg(components);
 
  113   bool applyPlanningScenePython(
const py_bindings_tools::ByteString& ps_str)
 
  115     moveit_msgs::PlanningScene ps_msg;
 
  117     return applyPlanningScene(ps_msg);
 
  121 static void wrap_planning_scene_interface()
 
  123   bp::class_<PlanningSceneInterfaceWrapper> planning_scene_class(
"PlanningSceneInterface",
 
  124                                                                  bp::init<bp::optional<std::string>>());
 
  126   planning_scene_class.def(
"get_known_object_names", &PlanningSceneInterfaceWrapper::getKnownObjectNamesPython);
 
  127   planning_scene_class.def(
"get_known_object_names_in_roi",
 
  128                            &PlanningSceneInterfaceWrapper::getKnownObjectNamesInROIPython);
 
  129   planning_scene_class.def(
"get_object_poses", &PlanningSceneInterfaceWrapper::getObjectPosesPython);
 
  130   planning_scene_class.def(
"get_objects", &PlanningSceneInterfaceWrapper::getObjectsPython);
 
  131   planning_scene_class.def(
"get_attached_objects", &PlanningSceneInterfaceWrapper::getAttachedObjectsPython);
 
  132   planning_scene_class.def(
"get_planning_scene", &PlanningSceneInterfaceWrapper::getPlanningScenePython);
 
  133   planning_scene_class.def(
"apply_planning_scene", &PlanningSceneInterfaceWrapper::applyPlanningScenePython);
 
  134   planning_scene_class.def(
"clear", &PlanningSceneInterfaceWrapper::clear);
 
  142   wrap_planning_scene_interface();