diff --git a/core/doc/conf.py b/core/doc/conf.py index 3ac17bdb..c65acd4e 100644 --- a/core/doc/conf.py +++ b/core/doc/conf.py @@ -33,7 +33,9 @@ extensions = [ ] autosummary_generate = True -autoclass_content = "both" # Add __init__ doc (ie. params) to class summaries +# Only add class doc in docstring as this is needed to clean up the +# constructor signature +autoclass_content = "class" # Remove 'view source code' from top of page (for html, not python) html_show_sourcelink = True autodoc_inherit_docstrings = True # If no docstring, inherit from base class diff --git a/core/python/bindings/src/module.cpp b/core/python/bindings/src/module.cpp index c3e4eb51..e300e4e7 100644 --- a/core/python/bindings/src/module.cpp +++ b/core/python/bindings/src/module.cpp @@ -50,7 +50,9 @@ PYBIND11_MODULE(pymoveit_mtc, m) { // options.show_user_defined_docstrings(); auto msub = m.def_submodule("core", "MoveIt Task Contructor Core"); msub.doc() = R"pbdoc( - Core components such as base types of stage- + This python package contains + core components such as + base types of stage- and planner classes. )pbdoc"; @@ -60,9 +62,13 @@ PYBIND11_MODULE(pymoveit_mtc, m) { msub = m.def_submodule("stages", "MoveIt Task Constructor Stages"); msub.doc() = R"pbdoc( - Contains all stages that + This python package contains + all stages that are available to the user. - The arrangement of stages + To use a stage, create an instance, then + add it to the task hierarchy at the + desired spot. + The arrangement of stages in the hierarchy define the task to be carried out. )pbdoc"; moveit::python::export_stages(msub); diff --git a/core/python/bindings/src/stages.cpp b/core/python/bindings/src/stages.cpp index 143c8f02..d6e809cc 100644 --- a/core/python/bindings/src/stages.cpp +++ b/core/python/bindings/src/stages.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include @@ -127,13 +128,32 @@ void export_stages(pybind11::module& m) { // clang-format on properties::class_(m, "CurrentState", R"pbdoc( + CurrentState(self, name) + Fetch the current PlanningScene state via get_planning_scene service. + + :: + + # create a stage instance + currentState = CurrentState('current state') + )pbdoc") - .def(py::init(), py::arg("name") = std::string("current state"), - "class CurrentState(self, name)"); + .def(py::init(), py::arg("name") = std::string("current state")); properties::class_(m, "FixedState", R"pbdoc( - Spawn a pre - defined PlanningScene state. + FixedState(self, name) + + Spawn a pre-defined PlanningScene state. + + :: + + # create a stage instance + fixedState = FixedState('fixed state') + + )pbdoc") + .def("setState", &FixedState::setState, R"pbdoc( + Use a planning scene pointer to specify which state the Fixed State + stage should have. )pbdoc") .def(py::init(), py::arg("name") = std::string("fixed state")); @@ -148,24 +168,27 @@ void export_stages(pybind11::module& m) { ; properties::class_(m, "ComputeIK", R"pbdoc( - Wrapper for any pose generator stage to compute IK poses - for a cartesian pose. + ComputeIK(self, name, stage) - The wrapper reads a target_pose from the interface state of - solutions provided by the wrapped stage. - This Cartesian pose (PoseStamped msg) is used as a goal pose - for inverse kinematics. + Wrapper for any pose generator stage to compute the inverse + kinematics for a pose in Cartesian space. + + The wrapper reads a ``target_pose`` from the interface state of + solutions provided by the wrapped stage. This cartesian pose + (``PoseStamped`` msg) is used as a goal pose for inverse + kinematics. Usually, the end effector's parent link or the group's tip link - is used as the IK frame, which should be moved to the goal frame. - However, any other IK frame can be defined (which is linked to the tip of the group). + is used as the inverse kinematics frame, which should be + moved to the goal frame. However, any other inverse kinematics + frame can be defined (which is linked to the tip of the group). - Properties of the internally received InterfaceState can be - forwarded to the newly generated, externally exposed InterfaceState. + Properties of the internally received ``InterfaceState`` can be + forwarded to the newly generated, externally exposed ``InterfaceState``. )pbdoc") .property("eef", R"pbdoc( - str: Specify which end effector should - be used. + str: Specify which end effector of the active planning group + should be used. )pbdoc") .property("group", R"pbdoc( str: Specify which planning group @@ -173,7 +196,7 @@ void export_stages(pybind11::module& m) { )pbdoc") .property("default_pose", R"pbdoc( str: Default joint pose of the active group - (defines cost of IK). + (defines cost of the inverse kinematics). )pbdoc") .property("max_ik_solutions", R"pbdoc( int: Set the maximum number of inverse @@ -184,15 +207,19 @@ void export_stages(pybind11::module& m) { the planning scene are allowed. )pbdoc") .property("ik_frame", R"pbdoc( - geometry_msgs/PoseStamped: Specify the frame with respect + 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 )pbdoc") .property("target_pose", R"pbdoc( - geometry_msgs/PoseStamped: Specify the pose on which + PoseStamped_ : Specify the pose on which the inverse kinematics should be calculated on. Since this property should almost always be set in the Interface State which is sent by the child, if possible, avoid setting it manually. + + .. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html )pbdoc") // methods of base class py::class_ need to be called last! .def(py::init()); @@ -232,13 +259,30 @@ void export_stages(pybind11::module& m) { Move specified joint variables by given amount. )pbdoc"); - py::enum_(m, "MergeMode") + py::enum_(m, "MergeMode", R"pbdoc( + )pbdoc") .value("SEQUENTIAL", stages::Connect::MergeMode::SEQUENTIAL) .value("WAYPOINTS", stages::Connect::MergeMode::WAYPOINTS); PropertyConverter(); properties::class_(m, "Connect", R"pbdoc( - Connect arbitrary InterfaceStates by motion planning + Connect(self, name, planners) + + Connect arbitrary InterfaceStates by motion planning. + You can specify the planning groups and the planners you + want to utilize: + + :: + + # Create a planner instance + samplingPlanner = PipelinePlanner() + # Specify group-planner combinations + planners = [ + ('foo_group', samplingPlanner), + ('bar_group', samplingPlanner) + ] + # create a stage instance + connect = Connect('connect', planners) The states may differ in various planning groups. To connect both states, the planners provided for @@ -247,6 +291,7 @@ void export_stages(pybind11::module& m) { planning group. Finally, an attempt is made to merge the sub trajectories of individual planning results. If this fails, the sequential planning result is returned. + )pbdoc") .def(py::init(), py::arg("name") = std::string("connect"), py::arg("planners")); @@ -260,13 +305,29 @@ void export_stages(pybind11::module& m) { )pbdoc") .def(py::init(), py::arg("name") = std::string("fix collisions")); - properties::class_(m, "GenerateGraspPose") - .property("object") - .property("eef") - .property("pregrasp") - .property("grasp") - .property("angle_delta") - .def(py::init()); + properties::class_(m, "GenerateGraspPose", R"pbdoc( + GenerateGraspPose(name) + + GenerateGraspPose stage derives from monitoring generator and can + be used to generate poses for grasping. Set the desired attributes + of the grasp using the stages properties. + )pbdoc") + .property("object", R"pbdoc( + str: Name of the Object in the planning scene, which should be grasped. + )pbdoc") + .property("eef", R"pbdoc( + str: Name of the end effector that should be used for grasping. + )pbdoc") + .property("pregrasp", R"pbdoc( + str: Name of the pre-grasp pose. + )pbdoc") + .property("grasp", R"pbdoc( + str: Name of the grasp pose. + )pbdoc") + .property("angle_delta", R"pbdoc( + double: Angular step distance in rad with which positions around the object are sampled. + )pbdoc") + .def(py::init(), py::arg("name") = std::string("Generate Grasp Pose")); properties::class_(m, "GeneratePose") .property("pose")