diff --git a/core/python/bindings/src/stages.cpp b/core/python/bindings/src/stages.cpp index 27af72e9..df5cf0e0 100644 --- a/core/python/bindings/src/stages.cpp +++ b/core/python/bindings/src/stages.cpp @@ -59,6 +59,7 @@ PYBIND11_SMART_HOLDER_TYPE_CASTERS(GeneratePlacePose) PYBIND11_SMART_HOLDER_TYPE_CASTERS(GeneratePose) PYBIND11_SMART_HOLDER_TYPE_CASTERS(Pick) PYBIND11_SMART_HOLDER_TYPE_CASTERS(Place) +PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleGraspBase) PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleGrasp) PYBIND11_SMART_HOLDER_TYPE_CASTERS(SimpleUnGrasp) @@ -473,7 +474,36 @@ void export_stages(pybind11::module& m) { .def(py::init(), "place_generator"_a, "name"_a = std::string("place")); - properties::class_(m, "SimpleGrasp", R"( + properties::class_(m, "SimpleGraspBase", "Abstract base class for grasping and releasing") + .property("eef", "str: The end effector of the robot") + .property("object", "str: The object to grasp (Must be present in the planning scene)") + .property("ik_frame", R"( + PoseStamped_: Set the frame for which the inverse kinematics is calculated + with respect to each pose generated by the pose_generator. + + .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html + )") + .def("setIKFrame", &SimpleGraspBase::setIKFrame, R"( + Set the frame as a PoseStamped_ for which the inverse kinematics are calculated with respect to + each pose generated by the pose_generator. + + .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html + )", "transform"_a) + .def("setIKFrame", &SimpleGraspBase::setIKFrame, R"( + Set the frame as a PoseStamped_ for which the inverse kinematics are calculated + with respect to each pose generated by the pose_generator. + + .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html + )", "pose"_a, "link"_a) + .def("setIKFrame", &SimpleGraspBase::setIKFrame, R"( + Set the frame for which the inverse kinematics are calculated + with respect to each pose generated by the pose_generator. + )", "link"_a) + .def("setMaxIKSolutions", &SimpleGraspBase::setMaxIKSolutions, R"( + Set the maximum number of inverse kinematics solutions that should be computed. + )", "max_ik_solutions"_a) + ; + properties::class_(m, "SimpleGrasp", R"( Specialization of SimpleGraspBase to realize grasping. Take a look at the :ref:`Pick and Place Tutorial ` for an in-depth look, @@ -481,40 +511,10 @@ void export_stages(pybind11::module& m) { of a task hierarchy that makes use of the ``SimpleGrasp`` stage. )") - .property("eef", "str: The end effector of the robot") - .property("object", "str: The object to grasp (Must be present in the planning scene)") - .property("ik_frame", R"( - PoseStamped_: Set the frame for which - the inverse kinematics are calculated - with respect to each pose generated by - the pose_generator. - - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )") .def(py::init(), "pose_generator"_a, - "name"_a = std::string("grasp generator")) - .def("setIKFrame", &SimpleGrasp::setIKFrame, R"( - Set the frame as a PoseStamped_ for which the inverse kinematics are calculated with respect to - each pose generated by the pose_generator. + "name"_a = std::string("grasp")); - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )", "transform"_a) - .def("setIKFrame", &SimpleGrasp::setIKFrame, R"( - Set the frame as a PoseStamped_ for which the inverse kinematics are calculated - with respect to each pose generated by the pose_generator. - - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )", "pose"_a, "link"_a) - .def("setIKFrame", &SimpleGrasp::setIKFrame, R"( - Set the frame for which the inverse kinematics are calculated - with respect to each pose generated by the pose_generator. - )", "link"_a) - .def("setMaxIKSolutions", &SimpleGrasp::setMaxIKSolutions, R"( - Set the maximum number of inverse kinematics solutions that - should be computed. - )", "max_ik_solutions"_a); - - properties::class_(m, "SimpleUnGrasp", R"( + properties::class_(m, "SimpleUnGrasp", R"( Specialization of SimpleGraspBase to realize ungrasping Take a look at the :ref:`Pick and Place Tutorial ` for an in-depth look, @@ -522,42 +522,10 @@ void export_stages(pybind11::module& m) { of a task hierarchy that makes use of the ``SimpleUnGrasp`` stage. )") - .property("eef", "str: The end effector of the robot") - .property("object", "str: The object to grasp (Must be present in the planning scene)") .property("pregrasp", "str: Name of the pre-grasp pose") .property("grasp", "str: Name of the grasp pose") - .property("ik_frame", R"( - PoseStamped_: Specify the frame with respect - to which the inverse kinematics - should be calculated. - - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )") - .def("setIKFrame", &SimpleUnGrasp::setIKFrame, R"( - Set the frame transform as a PoseStamped_ for which the inverse kinematics are calculated - with respect to each pose generated by the pose_generator. - - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )", "transform"_a) - .def("setIKFrame", &SimpleUnGrasp::setIKFrame, R"( - Set the frame transform as a PoseStamped_ in reference to a given link - for which the inverse kinematics are calculated - with respect to each pose generated by the pose_generator. - - .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html - )", "pose"_a, "link"_a) - .def("setIKFrame", &SimpleUnGrasp::setIKFrame, R"( - Set the frame for which the inverse kinematics are calculated - with respect to each pose generated by the pose_generator. - The IK Frame will be placed at the base frame of this link given - as an argument. - )", "link"_a) - .def("setMaxIKSolutions", &SimpleUnGrasp::setMaxIKSolutions, R"( - Set the maximum number of inverse kinematics solutions that - should be computed. - )", "max_ik_solutions"_a) - .def(py::init(), "pose_generator"_a, - "name"_a = std::string("place generator")); + .def(py::init(), "pose_generator"_a, + "name"_a = std::string("ungrasp")); } } // namespace python } // namespace moveit