add docstrings, custom signatures

This commit is contained in:
cpetersmeier 2021-09-18 18:53:36 +02:00 committed by Robert Haschke
parent d1c947c973
commit 0e7f2d5981
3 changed files with 100 additions and 31 deletions

View File

@ -33,7 +33,9 @@ extensions = [
] ]
autosummary_generate = True 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) # Remove 'view source code' from top of page (for html, not python)
html_show_sourcelink = True html_show_sourcelink = True
autodoc_inherit_docstrings = True # If no docstring, inherit from base class autodoc_inherit_docstrings = True # If no docstring, inherit from base class

View File

@ -50,7 +50,9 @@ PYBIND11_MODULE(pymoveit_mtc, m) {
// options.show_user_defined_docstrings(); // options.show_user_defined_docstrings();
auto msub = m.def_submodule("core", "MoveIt Task Contructor Core"); auto msub = m.def_submodule("core", "MoveIt Task Contructor Core");
msub.doc() = R"pbdoc( 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. and planner classes.
)pbdoc"; )pbdoc";
@ -60,9 +62,13 @@ PYBIND11_MODULE(pymoveit_mtc, m) {
msub = m.def_submodule("stages", "MoveIt Task Constructor Stages"); msub = m.def_submodule("stages", "MoveIt Task Constructor Stages");
msub.doc() = R"pbdoc( msub.doc() = R"pbdoc(
Contains all stages that This python package contains
all stages that
are available to the user. 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. define the task to be carried out.
)pbdoc"; )pbdoc";
moveit::python::export_stages(msub); moveit::python::export_stages(msub);

View File

@ -37,6 +37,7 @@
#include <moveit/task_constructor/stages.h> #include <moveit/task_constructor/stages.h>
#include <moveit/task_constructor/stages/pick.h> #include <moveit/task_constructor/stages/pick.h>
#include <moveit/task_constructor/stages/simple_grasp.h> #include <moveit/task_constructor/stages/simple_grasp.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit_msgs/PlanningScene.h> #include <moveit_msgs/PlanningScene.h>
#include <pybind11/stl.h> #include <pybind11/stl.h>
@ -127,13 +128,32 @@ void export_stages(pybind11::module& m) {
// clang-format on // clang-format on
properties::class_<CurrentState, Stage>(m, "CurrentState", R"pbdoc( properties::class_<CurrentState, Stage>(m, "CurrentState", R"pbdoc(
CurrentState(self, name)
Fetch the current PlanningScene state via get_planning_scene service. Fetch the current PlanningScene state via get_planning_scene service.
::
# create a stage instance
currentState = CurrentState('current state')
)pbdoc") )pbdoc")
.def(py::init<const std::string&>(), py::arg("name") = std::string("current state"), .def(py::init<const std::string&>(), py::arg("name") = std::string("current state"));
"class CurrentState(self, name)");
properties::class_<FixedState, Stage>(m, "FixedState", R"pbdoc( properties::class_<FixedState, Stage>(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") )pbdoc")
.def(py::init<const std::string&>(), py::arg("name") = std::string("fixed state")); .def(py::init<const std::string&>(), py::arg("name") = std::string("fixed state"));
@ -148,24 +168,27 @@ void export_stages(pybind11::module& m) {
; ;
properties::class_<ComputeIK, Stage>(m, "ComputeIK", R"pbdoc( properties::class_<ComputeIK, Stage>(m, "ComputeIK", R"pbdoc(
Wrapper for any pose generator stage to compute IK poses ComputeIK(self, name, stage)
for a cartesian pose.
The wrapper reads a target_pose from the interface state of Wrapper for any pose generator stage to compute the inverse
solutions provided by the wrapped stage. kinematics for a pose in Cartesian space.
This Cartesian pose (PoseStamped msg) is used as a goal pose
for inverse kinematics. 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 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. is used as the inverse kinematics frame, which should be
However, any other IK frame can be defined (which is linked to the tip of the group). 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 Properties of the internally received ``InterfaceState`` can be
forwarded to the newly generated, externally exposed InterfaceState. forwarded to the newly generated, externally exposed ``InterfaceState``.
)pbdoc") )pbdoc")
.property<std::string>("eef", R"pbdoc( .property<std::string>("eef", R"pbdoc(
str: Specify which end effector should str: Specify which end effector of the active planning group
be used. should be used.
)pbdoc") )pbdoc")
.property<std::string>("group", R"pbdoc( .property<std::string>("group", R"pbdoc(
str: Specify which planning group str: Specify which planning group
@ -173,7 +196,7 @@ void export_stages(pybind11::module& m) {
)pbdoc") )pbdoc")
.property<std::string>("default_pose", R"pbdoc( .property<std::string>("default_pose", R"pbdoc(
str: Default joint pose of the active group str: Default joint pose of the active group
(defines cost of IK). (defines cost of the inverse kinematics).
)pbdoc") )pbdoc")
.property<uint32_t>("max_ik_solutions", R"pbdoc( .property<uint32_t>("max_ik_solutions", R"pbdoc(
int: Set the maximum number of inverse int: Set the maximum number of inverse
@ -184,15 +207,19 @@ void export_stages(pybind11::module& m) {
the planning scene are allowed. the planning scene are allowed.
)pbdoc") )pbdoc")
.property<geometry_msgs::PoseStamped>("ik_frame", R"pbdoc( .property<geometry_msgs::PoseStamped>("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. to which the inverse kinematics should be calculated.
.. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html
)pbdoc") )pbdoc")
.property<geometry_msgs::PoseStamped>("target_pose", R"pbdoc( .property<geometry_msgs::PoseStamped>("target_pose", R"pbdoc(
geometry_msgs/PoseStamped: Specify the pose on which PoseStamped_ : Specify the pose on which
the inverse kinematics should be the inverse kinematics should be
calculated on. Since this property should almost always be set calculated on. Since this property should almost always be set
in the Interface State which is sent by the child, in the Interface State which is sent by the child,
if possible, avoid setting it manually. if possible, avoid setting it manually.
.. _PoseStamped: https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html
)pbdoc") )pbdoc")
// methods of base class py::class_ need to be called last! // methods of base class py::class_ need to be called last!
.def(py::init<const std::string&, Stage::pointer&&>()); .def(py::init<const std::string&, Stage::pointer&&>());
@ -232,13 +259,30 @@ void export_stages(pybind11::module& m) {
Move specified joint variables by given amount. Move specified joint variables by given amount.
)pbdoc"); )pbdoc");
py::enum_<stages::Connect::MergeMode>(m, "MergeMode") py::enum_<stages::Connect::MergeMode>(m, "MergeMode", R"pbdoc(
)pbdoc")
.value("SEQUENTIAL", stages::Connect::MergeMode::SEQUENTIAL) .value("SEQUENTIAL", stages::Connect::MergeMode::SEQUENTIAL)
.value("WAYPOINTS", stages::Connect::MergeMode::WAYPOINTS); .value("WAYPOINTS", stages::Connect::MergeMode::WAYPOINTS);
PropertyConverter<stages::Connect::MergeMode>(); PropertyConverter<stages::Connect::MergeMode>();
properties::class_<Connect, Stage>(m, "Connect", R"pbdoc( properties::class_<Connect, Stage>(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. The states may differ in various planning groups.
To connect both states, the planners provided for 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 planning group. Finally, an attempt is made to merge the
sub trajectories of individual planning results. sub trajectories of individual planning results.
If this fails, the sequential planning result is returned. If this fails, the sequential planning result is returned.
)pbdoc") )pbdoc")
.def(py::init<const std::string&, const Connect::GroupPlannerVector&>(), .def(py::init<const std::string&, const Connect::GroupPlannerVector&>(),
py::arg("name") = std::string("connect"), py::arg("planners")); py::arg("name") = std::string("connect"), py::arg("planners"));
@ -260,13 +305,29 @@ void export_stages(pybind11::module& m) {
)pbdoc") )pbdoc")
.def(py::init<const std::string&>(), py::arg("name") = std::string("fix collisions")); .def(py::init<const std::string&>(), py::arg("name") = std::string("fix collisions"));
properties::class_<GenerateGraspPose, MonitoringGenerator>(m, "GenerateGraspPose") properties::class_<GenerateGraspPose, MonitoringGenerator>(m, "GenerateGraspPose", R"pbdoc(
.property<std::string>("object") GenerateGraspPose(name)
.property<std::string>("eef")
.property<std::string>("pregrasp") GenerateGraspPose stage derives from monitoring generator and can
.property<std::string>("grasp") be used to generate poses for grasping. Set the desired attributes
.property<double>("angle_delta") of the grasp using the stages properties.
.def(py::init<const std::string&>()); )pbdoc")
.property<std::string>("object", R"pbdoc(
str: Name of the Object in the planning scene, which should be grasped.
)pbdoc")
.property<std::string>("eef", R"pbdoc(
str: Name of the end effector that should be used for grasping.
)pbdoc")
.property<std::string>("pregrasp", R"pbdoc(
str: Name of the pre-grasp pose.
)pbdoc")
.property<std::string>("grasp", R"pbdoc(
str: Name of the grasp pose.
)pbdoc")
.property<double>("angle_delta", R"pbdoc(
double: Angular step distance in rad with which positions around the object are sampled.
)pbdoc")
.def(py::init<const std::string&>(), py::arg("name") = std::string("Generate Grasp Pose"));
properties::class_<GeneratePose, MonitoringGenerator>(m, "GeneratePose") properties::class_<GeneratePose, MonitoringGenerator>(m, "GeneratePose")
.property<geometry_msgs::PoseStamped>("pose") .property<geometry_msgs::PoseStamped>("pose")