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(bp::list object_ids)
77 std::map<std::string, std::string> ser_ops;
78 for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = ops.begin(); it != ops.end(); ++it)
84 bp::dict getObjectsPython(bp::list object_ids)
86 std::map<std::string, moveit_msgs::CollisionObject> objs =
88 std::map<std::string, std::string> 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, std::string> ser_aobjs;
100 for (std::map<std::string, moveit_msgs::AttachedCollisionObject>::const_iterator it = aobjs.begin();
101 it != aobjs.end(); ++it)
107 bool applyPlanningScenePython(
const std::string& ps_str)
109 moveit_msgs::PlanningScene ps_msg;
111 return applyPlanningScene(ps_msg);
115 static void wrap_planning_scene_interface()
117 bp::class_<PlanningSceneInterfaceWrapper> PlanningSceneClass(
"PlanningSceneInterface",
118 bp::init<bp::optional<std::string>>());
120 PlanningSceneClass.def(
"get_known_object_names", &PlanningSceneInterfaceWrapper::getKnownObjectNamesPython);
121 PlanningSceneClass.def(
"get_known_object_names_in_roi",
122 &PlanningSceneInterfaceWrapper::getKnownObjectNamesInROIPython);
123 PlanningSceneClass.def(
"get_object_poses", &PlanningSceneInterfaceWrapper::getObjectPosesPython);
124 PlanningSceneClass.def(
"get_objects", &PlanningSceneInterfaceWrapper::getObjectsPython);
125 PlanningSceneClass.def(
"get_attached_objects", &PlanningSceneInterfaceWrapper::getAttachedObjectsPython);
126 PlanningSceneClass.def(
"apply_planning_scene", &PlanningSceneInterfaceWrapper::applyPlanningScenePython);
134 wrap_planning_scene_interface();
BOOST_PYTHON_MODULE(_moveit_roscpp_initializer)
Simple interface to MoveIt! components.