42 #include <boost/python.hpp>
53 class PlanningSceneInterfaceWrapper :
protected py_bindings_tools::ROScppInitializer,
public PlanningSceneInterface
57 PlanningSceneInterfaceWrapper(
const std::string& ns =
"")
58 : py_bindings_tools::ROScppInitializer(), PlanningSceneInterface(ns)
62 bp::list getKnownObjectNamesPython(
bool with_type =
false)
67 bp::list getKnownObjectNamesInROIPython(
double minx,
double miny,
double minz,
double maxx,
double maxy,
double maxz,
68 bool with_type =
false)
73 bp::dict getObjectPosesPython(
const bp::list& object_ids)
76 std::map<std::string, py_bindings_tools::ByteString> ser_ops;
77 for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = ops.begin(); it != ops.end(); ++it)
83 bp::dict getObjectsPython(
const bp::list& object_ids)
85 std::map<std::string, moveit_msgs::msg::CollisionObject> objs =
87 std::map<std::string, py_bindings_tools::ByteString> ser_objs;
88 for (std::map<std::string, moveit_msgs::msg::CollisionObject>::const_iterator it = objs.begin(); it != objs.end();
95 bp::dict getAttachedObjectsPython(
const bp::list& object_ids)
97 std::map<std::string, moveit_msgs::msg::AttachedCollisionObject> aobjs =
99 std::map<std::string, py_bindings_tools::ByteString> ser_aobjs;
100 for (std::map<std::string, moveit_msgs::msg::AttachedCollisionObject>::const_iterator it = aobjs.begin();
101 it != aobjs.end(); ++it)
107 bool applyPlanningScenePython(
const py_bindings_tools::ByteString& ps_str)
109 moveit_msgs::msg::PlanningScene ps_msg;
111 return applyPlanningScene(ps_msg);
115 static void wrap_planning_scene_interface()
117 bp::class_<PlanningSceneInterfaceWrapper> planning_scene_class(
"PlanningSceneInterface",
118 bp::init<bp::optional<std::string>>());
120 planning_scene_class.def(
"get_known_object_names", &PlanningSceneInterfaceWrapper::getKnownObjectNamesPython);
121 planning_scene_class.def(
"get_known_object_names_in_roi",
122 &PlanningSceneInterfaceWrapper::getKnownObjectNamesInROIPython);
123 planning_scene_class.def(
"get_object_poses", &PlanningSceneInterfaceWrapper::getObjectPosesPython);
124 planning_scene_class.def(
"get_objects", &PlanningSceneInterfaceWrapper::getObjectsPython);
125 planning_scene_class.def(
"get_attached_objects", &PlanningSceneInterfaceWrapper::getAttachedObjectsPython);
126 planning_scene_class.def(
"apply_planning_scene", &PlanningSceneInterfaceWrapper::applyPlanningScenePython);
134 wrap_planning_scene_interface();
Simple interface to MoveIt components.
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
BOOST_PYTHON_MODULE(_moveit_roscpp_initializer)