Skip to content

Commit

Permalink
Update definitions to pybind11
Browse files Browse the repository at this point in the history
  • Loading branch information
cambel committed Oct 9, 2024
1 parent 66b9b5d commit 7574ad8
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 117 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -285,10 +285,7 @@ PYBIND11_MODULE(pymoveit_move_group_interface, m)
.def("async_execute",
py::overload_cast<const moveit_msgs::RobotTrajectory&>(&MoveGroupInterfaceWrapper::asyncExecute),
py::arg("trajectory"))
move_group_interface_class.def("wait_for_motion_result", &MoveGroupInterfaceWrapper::waitForMotionResultPython);
moveit::core::MoveItErrorCode (MoveGroupInterfaceWrapper::*pick_1)(const std::string&, bool) =
&MoveGroupInterfaceWrapper::pick;

.def("wait_for_motion_result", &MoveGroupInterfaceWrapper::waitForMotionResultPython)
.def("pick",
py::overload_cast<const std::string&, std::vector<moveit_msgs::Grasp>, bool>(
&MoveGroupInterfaceWrapper::pick),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,121 +61,8 @@ class PlanningSceneInterfaceWrapper : protected py_binding_tools::ROScppInitiali
: py_binding_tools::ROScppInitializer(), PlanningSceneInterface(ns)
{
}

bp::list getKnownObjectNamesPython(bool with_type = false)
{
return py_bindings_tools::listFromString(getKnownObjectNames(with_type));
}

bp::list getKnownObjectNamesInROIPython(double minx, double miny, double minz, double maxx, double maxy, double maxz,
bool with_type = false)
{
return py_bindings_tools::listFromString(getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type));
}

bp::dict getObjectPosesPython(const bp::list& object_ids)
{
std::map<std::string, geometry_msgs::Pose> ops = getObjectPoses(py_bindings_tools::stringFromList(object_ids));
std::map<std::string, py_bindings_tools::ByteString> ser_ops;
for (std::map<std::string, geometry_msgs::Pose>::const_iterator it = ops.begin(); it != ops.end(); ++it)
ser_ops[it->first] = py_bindings_tools::serializeMsg(it->second);

return py_bindings_tools::dictFromType(ser_ops);
}

bp::dict getObjectsPython(const bp::list& object_ids)
{
std::map<std::string, moveit_msgs::CollisionObject> objs =
getObjects(py_bindings_tools::stringFromList(object_ids));
std::map<std::string, py_bindings_tools::ByteString> ser_objs;
for (std::map<std::string, moveit_msgs::CollisionObject>::const_iterator it = objs.begin(); it != objs.end(); ++it)
ser_objs[it->first] = py_bindings_tools::serializeMsg(it->second);

return py_bindings_tools::dictFromType(ser_objs);
}

bool allowCollisionsPython1(const std::string& link_1, const std::string& link_2)
{
return allowCollisions(link_1, link_2);
}

bool allowCollisionsPython2(const bp::list& links, const std::string& link_2)
{
std::vector<std::string> links_ = py_bindings_tools::stringFromList(links);
return allowCollisions(links_, link_2);
}

bool disallowCollisionsPython1(const std::string& link_1, const std::string& link_2)
{
return disallowCollisions(link_1, link_2);
}

bool disallowCollisionsPython2(const bp::list& links, const std::string& link_2)
{
std::vector<std::string> links_ = py_bindings_tools::stringFromList(links);
return disallowCollisions(links_, link_2);
}

bool setCollisionsPython1(bool set_to_allow, const std::string& link_1, const bp::list links)
{
std::vector<std::string> links_ = py_bindings_tools::stringFromList(links);
return setCollisions(set_to_allow, link_1, links_);
}

bool setCollisionsPython2(bool set_to_allow, const bp::list& links_1, const bp::list links_2)
{
std::vector<std::string> links_1_ = py_bindings_tools::stringFromList(links_1);
std::vector<std::string> links_2_ = py_bindings_tools::stringFromList(links_2);
return setCollisions(set_to_allow, links_1_, links_2_);
}

bp::dict getAttachedObjectsPython(const bp::list& object_ids)
{
std::map<std::string, moveit_msgs::AttachedCollisionObject> aobjs =
getAttachedObjects(py_bindings_tools::stringFromList(object_ids));
std::map<std::string, py_bindings_tools::ByteString> ser_aobjs;
for (std::map<std::string, moveit_msgs::AttachedCollisionObject>::const_iterator it = aobjs.begin();
it != aobjs.end(); ++it)
ser_aobjs[it->first] = py_bindings_tools::serializeMsg(it->second);

return py_bindings_tools::dictFromType(ser_aobjs);
}

bool applyCollisionObjectPython(const py_bindings_tools::ByteString& msg_bytestring)
{
moveit_msgs::CollisionObject co_msg;
py_bindings_tools::deserializeMsg(msg_bytestring, co_msg);
return applyCollisionObject(co_msg);
}

bool applyPlanningScenePython(const py_bindings_tools::ByteString& ps_str)
{
moveit_msgs::PlanningScene ps_msg;
py_bindings_tools::deserializeMsg(ps_str, ps_msg);
return applyPlanningScene(ps_msg);
}
};

static void wrap_planning_scene_interface()
{
bp::class_<PlanningSceneInterfaceWrapper> planning_scene_class("PlanningSceneInterface",
bp::init<bp::optional<std::string>>());

planning_scene_class.def("get_known_object_names", &PlanningSceneInterfaceWrapper::getKnownObjectNamesPython);
planning_scene_class.def("get_known_object_names_in_roi",
&PlanningSceneInterfaceWrapper::getKnownObjectNamesInROIPython);
planning_scene_class.def("get_object_poses", &PlanningSceneInterfaceWrapper::getObjectPosesPython);
planning_scene_class.def("get_objects", &PlanningSceneInterfaceWrapper::getObjectsPython);
planning_scene_class.def("allow_collisions", &PlanningSceneInterfaceWrapper::allowCollisionsPython1);
planning_scene_class.def("allow_collisions", &PlanningSceneInterfaceWrapper::allowCollisionsPython2);
planning_scene_class.def("disallow_collisions", &PlanningSceneInterfaceWrapper::disallowCollisionsPython1);
planning_scene_class.def("disallow_collisions", &PlanningSceneInterfaceWrapper::disallowCollisionsPython2);
planning_scene_class.def("set_collisions", &PlanningSceneInterfaceWrapper::setCollisionsPython1);
planning_scene_class.def("set_collisions", &PlanningSceneInterfaceWrapper::setCollisionsPython2);
planning_scene_class.def("get_attached_objects", &PlanningSceneInterfaceWrapper::getAttachedObjectsPython);
planning_scene_class.def("apply_collision_object", &PlanningSceneInterfaceWrapper::applyCollisionObjectPython);
planning_scene_class.def("apply_planning_scene", &PlanningSceneInterfaceWrapper::applyPlanningScenePython);
}
} // namespace planning_interface
} // namespace moveit

Expand All @@ -200,6 +87,20 @@ PYBIND11_MODULE(pymoveit_planning_scene_interface, m)
.def("get_planning_scene", &PlanningSceneInterfaceWrapper::getPlanningSceneMsg)
.def("apply_planning_scene", &PlanningSceneInterface::applyPlanningScene, py::arg("planning_scene"))
.def("clear", &PlanningSceneInterfaceWrapper::clear)
.def("allow_collisions_python", py::overload_cast<const std::string&, const std::string&>(
&PlanningSceneInterface::allowCollisions), py::arg("link_1"), py::arg("link_2"))
.def("allow_collisions_python", py::overload_cast<const std::vector<std::string>&, const std::string&>(
&PlanningSceneInterface::allowCollisions), py::arg("link_1"), py::arg("link_2"))
.def("disallow_collisions", py::overload_cast<const std::string&, const std::string&>(
&PlanningSceneInterface::disallowCollisions), py::arg("link_1"), py::arg("link_2"))
.def("disallow_collisions", py::overload_cast<const std::vector<std::string>&, const std::string&>(
&PlanningSceneInterface::disallowCollisions), py::arg("link_1"), py::arg("link_2"))
.def("set_collisions", py::overload_cast<bool, const std::string&, const std::vector<std::string>&>(
&PlanningSceneInterface::setCollisions), py::arg("set_to_allow"), py::arg("link_1"), py::arg("link_2"))
.def("set_collisions", py::overload_cast<bool, const std::vector<std::string>&, const std::vector<std::string>&>(
&PlanningSceneInterface::setCollisions), py::arg("set_to_allow"), py::arg("link_1"), py::arg("link_2"))
.def("apply_collision_object", py::overload_cast<const moveit_msgs::CollisionObject&>(
&PlanningSceneInterface::applyCollisionObject), py::arg("collision_object"))
// keep semicolon on next line
;
}
Expand Down

0 comments on commit 7574ad8

Please sign in to comment.