From b630cef17fb4adafe32666569268d1083f12c2b2 Mon Sep 17 00:00:00 2001 From: Paul Sardin Date: Fri, 16 Jan 2026 08:54:45 +0100 Subject: [PATCH 1/3] Fix auto generating pyhpp doc based on doxygen --- doc/doxygen_xml_parser.py | 12 +++-- src/pyhpp/constraints/by-substitution.cc | 9 +++- .../constraints/explicit-constraint-set.cc | 5 +- src/pyhpp/constraints/implicit.cc | 21 ++++++-- src/pyhpp/constraints/iterative-solver.cc | 5 +- src/pyhpp/core/constraint.cc | 41 +++++++++++---- src/pyhpp/core/node.cc | 21 +++++--- src/pyhpp/core/path.cc | 32 +++++++----- src/pyhpp/core/roadmap.cc | 51 ++++++++++--------- 9 files changed, 129 insertions(+), 68 deletions(-) diff --git a/doc/doxygen_xml_parser.py b/doc/doxygen_xml_parser.py index 7079c793..7d374531 100644 --- a/doc/doxygen_xml_parser.py +++ b/doc/doxygen_xml_parser.py @@ -22,14 +22,16 @@ def classDoc(self, name): class ClassDoc: def __init__(self, filename): self.tree = etree.parse(filename) - self.compound = self.tree.find("/compounddef") + self.compound = self.tree.find("./compounddef") self.classname = self.compound.find("compoundname").text.strip() @staticmethod def _getDoc(el): b = el.find("briefdescription") d = el.find("detaileddescription") - return etree.tostring(b, method="text").strip(), d.text.strip() + brief = etree.tostring(b, method="text", encoding="unicode").strip() + detailed = d.text.strip() if d.text else "" + return brief, detailed def _getMember(self, sectionKind, memberDefKind, name): # return self.compound.xpath ("sectiondef[@kind='" + sectionKind @@ -76,14 +78,16 @@ def getClassMethodDoc(self, methodname): ] else: args = [] - args += [el.text.strip() for el in member.xpath("param/declname")] + args += [el.text.strip() for el in member.xpath("param/declname") if el.text] for parameters in dd.xpath("para/parameterlist/parameteritem"): pargs = [ el.text.strip() for el in parameters.find("parameternamelist").findall("parametername") + if el.text ] pns = " ".join(pargs) - pd = parameters.find("parameterdescription").find("para").text.strip() + para_el = parameters.find("parameterdescription").find("para") + pd = para_el.text.strip() if para_el is not None and para_el.text else "" d += "\n:param " + pns + ":" + pd return b, d, args diff --git a/src/pyhpp/constraints/by-substitution.cc b/src/pyhpp/constraints/by-substitution.cc index 4a74eed2..55a7d882 100644 --- a/src/pyhpp/constraints/by-substitution.cc +++ b/src/pyhpp/constraints/by-substitution.cc @@ -31,6 +31,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -52,15 +54,18 @@ void exposeBySubstitution() { .value("INFEASIBLE", HierarchicalIterative::INFEASIBLE) .value("SUCCESS", HierarchicalIterative::SUCCESS); + // DocClass(solver::BySubstitution) class_ >( "BySubstitution", init()) .def("explicitConstraintSetHasChanged", - &BySubstitution::explicitConstraintSetHasChanged) + &BySubstitution::explicitConstraintSetHasChanged, + DocClassMethod(explicitConstraintSetHasChanged)) .def("solve", &BySubstitution_solve) .def("explicitConstraintSet", static_cast( &BySubstitution::explicitConstraintSet), - return_internal_reference<>()) + return_internal_reference<>(), + DocClassMethod(explicitConstraintSet)) .add_property("errorThreshold", static_cast( &BySubstitution::errorThreshold), diff --git a/src/pyhpp/constraints/explicit-constraint-set.cc b/src/pyhpp/constraints/explicit-constraint-set.cc index 26578a83..032577ea 100644 --- a/src/pyhpp/constraints/explicit-constraint-set.cc +++ b/src/pyhpp/constraints/explicit-constraint-set.cc @@ -32,6 +32,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -39,10 +41,11 @@ namespace constraints { using namespace hpp::constraints; void exposeExplicitConstraintSet() { + // DocClass(ExplicitConstraintSet) class_("ExplicitConstraintSet", init()) .def("__str__", &to_str) - .def("add", &ExplicitConstraintSet::add); + .def("add", &ExplicitConstraintSet::add, DocClassMethod(add)); } } // namespace constraints } // namespace pyhpp diff --git a/src/pyhpp/constraints/implicit.cc b/src/pyhpp/constraints/implicit.cc index fca3a0dc..72aba304 100644 --- a/src/pyhpp/constraints/implicit.cc +++ b/src/pyhpp/constraints/implicit.cc @@ -37,6 +37,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -53,13 +55,22 @@ void exposeImplicit() { .value("EqualToZero", EqualToZero) .value("Superior", Superior) .value("Inferior", Inferior); + // DocClass(Implicit) class_("Implicit", no_init) .def("__init__", make_constructor(&Implicit::create)) - .PYHPP_DEFINE_GETTER_SETTER_INTERNAL_REF(Implicit, comparisonType, - const ComparisonTypes_t&) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Implicit, function) - .def("parameterSize", &Implicit::parameterSize) - .def("rightHandSideSize", &Implicit::rightHandSideSize) + .def("comparisonType", + static_cast( + &Implicit::comparisonType), + return_internal_reference<>()) + .def("comparisonType", + static_cast( + &Implicit::comparisonType)) + .def("function", &Implicit::function, return_internal_reference<>(), + DocClassMethod(function)) + .def("parameterSize", &Implicit::parameterSize, + DocClassMethod(parameterSize)) + .def("rightHandSideSize", &Implicit::rightHandSideSize, + DocClassMethod(rightHandSideSize)) .def("getFunctionOutputSize", &getFunctionOutputSize) .staticmethod("getFunctionOutputSize"); } diff --git a/src/pyhpp/constraints/iterative-solver.cc b/src/pyhpp/constraints/iterative-solver.cc index 6325ea48..f9e01d4c 100644 --- a/src/pyhpp/constraints/iterative-solver.cc +++ b/src/pyhpp/constraints/iterative-solver.cc @@ -37,6 +37,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -48,10 +50,11 @@ void exposeHierarchicalIterativeSolver() { class_("ComparisonTypes") .def(vector_indexing_suite()); + // DocClass(solver::HierarchicalIterative) class_("HierarchicalIterative", init()) .def("__str__", &to_str) - .def("add", &HierarchicalIterative::add) + .def("add", &HierarchicalIterative::add, DocClassMethod(add)) .add_property( "errorThreshold", diff --git a/src/pyhpp/core/constraint.cc b/src/pyhpp/core/constraint.cc index 60ec1d9c..86fc8e13 100644 --- a/src/pyhpp/core/constraint.cc +++ b/src/pyhpp/core/constraint.cc @@ -36,6 +36,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -85,41 +87,58 @@ static void setRightHandSideOfConstraint( } void exposeConstraint() { + // DocClass(Constraint) class_("Constraint", no_init) .def("__str__", &to_str_from_operator) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Constraint, name) - .PYHPP_DEFINE_METHOD(CWrapper, apply) + .def("name", &Constraint::name, return_internal_reference<>(), + DocClassMethod(name)) + .def("apply", &CWrapper::apply) .def("isSatisfied", &CWrapper::isSatisfied1) .def("isSatisfied", &CWrapper::isSatisfied2) - .PYHPP_DEFINE_METHOD(CWrapper, copy); + .def("copy", &CWrapper::copy); + // DocClass(ConstraintSet) class_ >("ConstraintSet", no_init) .def("__init__", make_constructor(&createConstraintSet)) - .PYHPP_DEFINE_METHOD(ConstraintSet, addConstraint) - .PYHPP_DEFINE_METHOD(ConstraintSet, configProjector); + .def("addConstraint", &ConstraintSet::addConstraint, + DocClassMethod(addConstraint)) + .def("configProjector", &ConstraintSet::configProjector, + DocClassMethod(configProjector)); + // DocClass(ConfigProjector) class_ >("ConfigProjector", no_init) .def("__init__", make_constructor(&createConfigProjector)) .def("solver", static_cast( &ConfigProjector::solver), - return_internal_reference<>()) - .def("add", &ConfigProjector::add) - .PYHPP_DEFINE_GETTER_SETTER(ConfigProjector, lastIsOptional, bool) - .PYHPP_DEFINE_GETTER_SETTER(ConfigProjector, maxIterations, size_type) + return_internal_reference<>(), DocClassMethod(solver)) + .def("add", &ConfigProjector::add, DocClassMethod(add)) + .def("lastIsOptional", + static_cast( + &ConfigProjector::lastIsOptional)) + .def("lastIsOptional", + static_cast( + &ConfigProjector::lastIsOptional)) + .def("maxIterations", + static_cast( + &ConfigProjector::maxIterations)) + .def("maxIterations", + static_cast( + &ConfigProjector::maxIterations)) .def("errorThreshold", static_cast( &ConfigProjector::errorThreshold)) .def("errorThreshold", static_cast( &ConfigProjector::errorThreshold)) - .PYHPP_DEFINE_METHOD(ConfigProjector, residualError) + .def("residualError", &ConfigProjector::residualError, + DocClassMethod(residualError)) .def("setRightHandSideFromConfig", &rightHandSideFromConfig) .def("setRightHandSideOfConstraint", &setRightHandSideOfConstraint) .def("sigma", &ConfigProjector::sigma, - return_value_policy()); + return_value_policy(), DocClassMethod(sigma)); } } // namespace core } // namespace pyhpp diff --git a/src/pyhpp/core/node.cc b/src/pyhpp/core/node.cc index d702fe20..1ffc5c56 100644 --- a/src/pyhpp/core/node.cc +++ b/src/pyhpp/core/node.cc @@ -34,6 +34,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -42,23 +44,26 @@ namespace core { using namespace hpp::core; void exposeNode() { + // DocClass(Node) class_, boost::noncopyable>("Node", no_init) .def(init()) .def(init()) - .PYHPP_DEFINE_METHOD(Node, addOutEdge) - .PYHPP_DEFINE_METHOD(Node, addInEdge) + .def("addOutEdge", &Node::addOutEdge, DocClassMethod(addOutEdge)) + .def("addInEdge", &Node::addInEdge, DocClassMethod(addInEdge)) .def("connectedComponent", static_cast( &Node::connectedComponent)) .def("connectedComponent", static_cast( &Node::connectedComponent)) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Node, outEdges) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Node, inEdges) - .PYHPP_DEFINE_METHOD(Node, isOutNeighbor) - .PYHPP_DEFINE_METHOD(Node, isInNeighbor) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Node, configuration) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Node, print); + .def("outEdges", &Node::outEdges, return_internal_reference<>(), + DocClassMethod(outEdges)) + .def("inEdges", &Node::inEdges, return_internal_reference<>(), + DocClassMethod(inEdges)) + .def("isOutNeighbor", &Node::isOutNeighbor, DocClassMethod(isOutNeighbor)) + .def("isInNeighbor", &Node::isInNeighbor, DocClassMethod(isInNeighbor)) + .def("configuration", &Node::configuration, return_internal_reference<>(), + DocClassMethod(configuration)); } } // namespace core } // namespace pyhpp diff --git a/src/pyhpp/core/path.cc b/src/pyhpp/core/path.cc index 66d55d77..9892e68c 100644 --- a/src/pyhpp/core/path.cc +++ b/src/pyhpp/core/path.cc @@ -36,6 +36,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -141,6 +143,7 @@ struct PathWrap : PathWrapper, wrapper { }; void exposePath() { + // DocClass(Path) class_, boost::noncopyable>("Path", no_init) .def("__str__", &to_str_from_operator) @@ -148,26 +151,29 @@ void exposePath() { .def("__call__", &PathWrap::py_call2) .def("eval", &PathWrap::py_call1) .def("eval", &PathWrap::py_call2) - .PYHPP_DEFINE_METHOD(PathWrap, derivative) + .def("derivative", &PathWrap::derivative) - .def("copy", static_cast(&Path::copy)) + .def("copy", static_cast(&Path::copy), + DocClassMethod(copy)) .def("extract", static_cast(&Path::extract)) + const>(&Path::extract), + DocClassMethod(extract)) .def("extract", static_cast( &Path::extract)) - // .PYHPP_DEFINE_METHOD (Path, timeRange) .def("timeRange", static_cast(&Path::timeRange), - return_internal_reference<>()) - .def("reverse", &Path::reverse) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Path, paramRange) - .PYHPP_DEFINE_METHOD(Path, length) - .PYHPP_DEFINE_METHOD(Path, initial) - .PYHPP_DEFINE_METHOD(Path, end) - .PYHPP_DEFINE_METHOD(PathWrap, constraints) - .PYHPP_DEFINE_METHOD(Path, outputSize) - .PYHPP_DEFINE_METHOD(Path, outputDerivativeSize); + return_internal_reference<>(), DocClassMethod(timeRange)) + .def("reverse", &Path::reverse, DocClassMethod(reverse)) + .def("paramRange", &Path::paramRange, return_internal_reference<>(), + DocClassMethod(paramRange)) + .def("length", &Path::length, DocClassMethod(length)) + .def("initial", &Path::initial, DocClassMethod(initial)) + .def("end", &Path::end, DocClassMethod(end)) + .def("constraints", &PathWrap::constraints) + .def("outputSize", &Path::outputSize, DocClassMethod(outputSize)) + .def("outputDerivativeSize", &Path::outputDerivativeSize, + DocClassMethod(outputDerivativeSize)); class_, hpp::shared_ptr, boost::noncopyable>( "PathWrap", no_init) diff --git a/src/pyhpp/core/roadmap.cc b/src/pyhpp/core/roadmap.cc index e7036c04..3e846343 100644 --- a/src/pyhpp/core/roadmap.cc +++ b/src/pyhpp/core/roadmap.cc @@ -33,6 +33,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -218,49 +220,52 @@ struct RWrapper { }; void exposeRoadmap() { + // DocClass(Roadmap) class_("Roadmap", no_init) .def("__init__", make_constructor(&Roadmap::create)) .def("__str__", &to_str) - .PYHPP_DEFINE_METHOD(Roadmap, clear) - .PYHPP_DEFINE_METHOD1(RWrapper, addNode, - return_value_policy()) + .def("clear", &Roadmap::clear, DocClassMethod(clear)) + .def("addNode", &RWrapper::addNode, + return_value_policy()) .def("nearestNode", &RWrapper::nearestNode1) .def("nearestNode", &RWrapper::nearestNode2) .def("nearestNode", &RWrapper::nearestNode3) .def("nearestNode", &RWrapper::nearestNode4) .def("nearestNodes", &RWrapper::nearestNodes1) .def("nearestNodes", &RWrapper::nearestNodes2) - .PYHPP_DEFINE_METHOD(Roadmap, nodesWithinBall) - .PYHPP_DEFINE_METHOD1(RWrapper, addNodeAndEdges, - return_value_policy()) - .PYHPP_DEFINE_METHOD1(RWrapper, addNodeAndEdge, - return_value_policy()) + .def("nodesWithinBall", &Roadmap::nodesWithinBall, + DocClassMethod(nodesWithinBall)) + .def("addNodeAndEdges", &RWrapper::addNodeAndEdges, + return_value_policy()) + .def("addNodeAndEdge", &RWrapper::addNodeAndEdge, + return_value_policy()) .def("addEdge", &RWrapper::addEdge) .def("addEdge", &RWrapper::addEdge2) - .PYHPP_DEFINE_METHOD(Roadmap, addEdges) + .def("addEdges", &Roadmap::addEdges, DocClassMethod(addEdges)) .def("merge", - static_cast(&Roadmap::merge)) - .PYHPP_DEFINE_METHOD(Roadmap, insertPathVector) - .PYHPP_DEFINE_METHOD1(Roadmap, addGoalNode, - return_value_policy()) - .PYHPP_DEFINE_METHOD(Roadmap, resetGoalNodes) - .PYHPP_DEFINE_METHOD(Roadmap, pathExists) + static_cast(&Roadmap::merge), + DocClassMethod(merge)) + .def("insertPathVector", &Roadmap::insertPathVector, + DocClassMethod(insertPathVector)) + .def("addGoalNode", &Roadmap::addGoalNode, + return_value_policy(), + DocClassMethod(addGoalNode)) + .def("resetGoalNodes", &Roadmap::resetGoalNodes, + DocClassMethod(resetGoalNodes)) + .def("pathExists", &Roadmap::pathExists, DocClassMethod(pathExists)) .def("nodes", &RWrapper::nodes) .def("nodesConnectedComponent", &RWrapper::nodesConnectedComponent) .def("initNode", &RWrapper::initNode1) .def("initNode", &RWrapper::initNode2, return_value_policy()) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Roadmap, goalNodes) + .def("goalNodes", &Roadmap::goalNodes, return_internal_reference<>(), + DocClassMethod(goalNodes)) .def("connectedComponents", &RWrapper::connectedComponents) - .PYHPP_DEFINE_METHOD_INTERNAL_REF(Roadmap, distance) + .def("distance", &Roadmap::distance, return_internal_reference<>(), + DocClassMethod(distance)) .def("numberConnectedComponents", &RWrapper::numberConnectedComponents) .def("getConnectedComponent", &RWrapper::getConnectedComponent) - .def("connectedComponentOfNode", &RWrapper::connectedComponentOfNode) - // .def("cost", &RWrapper::cost1) - // .def("cost", &RWrapper::cost2, - // return_value_policy()) - - ; + .def("connectedComponentOfNode", &RWrapper::connectedComponentOfNode); } } // namespace core } // namespace pyhpp From b7fd95c9ca03dc6911a2bc4c3b0dea6414c0e62f Mon Sep 17 00:00:00 2001 From: Paul Sardin Date: Mon, 26 Jan 2026 09:25:33 +0100 Subject: [PATCH 2/3] Expand DocClassMethod() usage and add it to relevant functions --- doc/configure.py | 8 +- doc/doxygen_xml_parser.py | 117 ++++++++++++++---- src/pyhpp/constraints/by-substitution.cc | 4 +- src/pyhpp/constraints/explicit.cc | 3 + .../constraints/generic-transformation.cc | 2 + src/pyhpp/constraints/implicit.cc | 2 +- src/pyhpp/constraints/locked-joint.cc | 2 + src/pyhpp/constraints/relative-com.cc | 6 +- src/pyhpp/core/config-validation.cc | 2 +- src/pyhpp/core/configuration-shooter.cc | 5 +- src/pyhpp/core/connected-component.cc | 10 +- src/pyhpp/core/distance.cc | 7 +- src/pyhpp/core/parameter.cc | 3 + src/pyhpp/core/path-optimizer.cc | 14 ++- src/pyhpp/core/path-planner.cc | 40 ++++-- src/pyhpp/core/path-projector.cc | 5 +- src/pyhpp/core/path-validation.cc | 5 +- src/pyhpp/core/path/spline.cc | 2 + src/pyhpp/core/path/vector.cc | 18 +-- src/pyhpp/core/problem-target.cc | 3 + src/pyhpp/core/problem.cc | 26 ++-- src/pyhpp/core/reports.cc | 7 ++ src/pyhpp/core/steering-method.cc | 10 +- src/pyhpp/manipulation/device.cc | 17 ++- src/pyhpp/manipulation/graph.cc | 12 +- src/pyhpp/manipulation/path-optimizer.cc | 2 + src/pyhpp/manipulation/path-planner.cc | 30 +++-- src/pyhpp/manipulation/path-projector.cc | 2 + src/pyhpp/manipulation/problem.cc | 5 +- src/pyhpp/manipulation/steering-method.cc | 2 + src/pyhpp/pinocchio/device.cc | 28 +++-- src/pyhpp/pinocchio/liegroup.cc | 45 ++++--- 32 files changed, 321 insertions(+), 123 deletions(-) diff --git a/doc/configure.py b/doc/configure.py index 068d108d..b9e95cd9 100755 --- a/doc/configure.py +++ b/doc/configure.py @@ -116,7 +116,13 @@ def _xmlDirFromPkgConfig(pkg): nsToPackage = { "hpp::core": _xmlDirFromPkgConfig("hpp-core"), + "hpp::core::path": _xmlDirFromPkgConfig("hpp-core"), "hpp::constraints": _xmlDirFromPkgConfig("hpp-constraints"), + "hpp::constraints::solver": _xmlDirFromPkgConfig("hpp-constraints"), + "hpp::pinocchio": _xmlDirFromPkgConfig("hpp-pinocchio"), + "hpp::manipulation": _xmlDirFromPkgConfig("hpp-manipulation"), + "hpp::manipulation::graph": _xmlDirFromPkgConfig("hpp-manipulation"), + "hpp::manipulation::pathPlanner": _xmlDirFromPkgConfig("hpp-manipulation"), } @@ -142,7 +148,7 @@ def make_doc_string(brief, detailled): def make_args_string(args): - return "(" + ",".join(['arg("' + a + '")' for a in args]) + ")" + return "(" + ",".join(['boost::python::arg("' + a + '")' for a in args]) + ")" def substitute(istr, ostr): diff --git a/doc/doxygen_xml_parser.py b/doc/doxygen_xml_parser.py index 7d374531..aa59cad5 100644 --- a/doc/doxygen_xml_parser.py +++ b/doc/doxygen_xml_parser.py @@ -16,14 +16,18 @@ def _getCompound(self, kind, name): def classDoc(self, name): el = self._getCompound("class", name) - return ClassDoc(path.join(self.directory, el.get("refid") + ".xml")) + return ClassDoc( + path.join(self.directory, el.get("refid") + ".xml"), self.directory + ) class ClassDoc: - def __init__(self, filename): + def __init__(self, filename, directory=None): self.tree = etree.parse(filename) self.compound = self.tree.find("./compounddef") self.classname = self.compound.find("compoundname").text.strip() + self.directory = directory if directory else path.dirname(filename) + self._group_cache = {} @staticmethod def _getDoc(el): @@ -33,30 +37,93 @@ def _getDoc(el): detailed = d.text.strip() if d.text else "" return brief, detailed + def _getMemberFromGroup(self, memberDefKind, name): + """Look for memberdef in a group file via member refid.""" + members = self.compound.xpath( + "sectiondef/member[@kind='" + memberDefKind + "' and name='" + name + "']" + ) + if not members: + return None + member = members[0] + refid = member.get("refid") + if not refid: + return None + group_id = refid.rsplit("_1", 1)[0] + if group_id not in self._group_cache: + group_file = path.join(self.directory, group_id + ".xml") + if not path.isfile(group_file): + return None + self._group_cache[group_id] = etree.parse(group_file) + group_tree = self._group_cache[group_id] + memberdefs = group_tree.xpath( + "//memberdef[@id='" + refid + "' and @kind='" + memberDefKind + "']" + ) + if memberdefs: + return memberdefs[0] + return None + + def _getMemberFromInherited(self, memberDefKind, name): + """Look for memberdef in base class XML via listofallmembers member refid.""" + members = self.compound.xpath( + "listofallmembers/member[name='" + name + "']" + ) + if not members: + return None + member = members[0] + refid = member.get("refid") + if not refid: + return None + # Extract base class file from refid + # e.g., "classhpp_1_1pinocchio_1_1AbstractDevice_1a312..." -> "classhpp_1_1pinocchio_1_1AbstractDevice" + parts = refid.rsplit("_1", 1) + if len(parts) < 2: + return None + base_class_id = parts[0] + base_class_file = path.join(self.directory, base_class_id + ".xml") + if not path.isfile(base_class_file): + return None + if base_class_id not in self._group_cache: + self._group_cache[base_class_id] = etree.parse(base_class_file) + base_tree = self._group_cache[base_class_id] + memberdefs = base_tree.xpath( + "//memberdef[@id='" + refid + "' and @kind='" + memberDefKind + "']" + ) + if memberdefs: + return memberdefs[0] + return None + def _getMember(self, sectionKind, memberDefKind, name): - # return self.compound.xpath ("sectiondef[@kind='" + sectionKind - try: - return self.compound.xpath( - "sectiondef[re:test(@kind,'" - + sectionKind - + "')]/memberdef[@kind='" - + memberDefKind - + "' and name='" - + name - + "']", - namespaces={"re": "http://exslt.org/regular-expressions"}, - )[0] - except IndexError as e: - msg = ( - "Error: Could not find member (" - + sectionKind - + ") " - + name - + " of class " - + self.classname - ) - print(msg + "\n" + str(e), file=sys.stderr) - raise IndexError(msg) + # First try to find memberdef directly in class XML + results = self.compound.xpath( + "sectiondef[re:test(@kind,'" + + sectionKind + + "')]/memberdef[@kind='" + + memberDefKind + + "' and name='" + + name + + "']", + namespaces={"re": "http://exslt.org/regular-expressions"}, + ) + if results: + return results[0] + # Fall back to looking in group files (for @ingroup documented classes) + memberdef = self._getMemberFromGroup(memberDefKind, name) + if memberdef is not None: + return memberdef + # Fall back to looking in base class files (for inherited methods) + memberdef = self._getMemberFromInherited(memberDefKind, name) + if memberdef is not None: + return memberdef + msg = ( + "Error: Could not find member (" + + sectionKind + + ") " + + name + + " of class " + + self.classname + ) + print(msg, file=sys.stderr) + raise IndexError(msg) def getClassDoc(self): return self._getDoc(self.compound) diff --git a/src/pyhpp/constraints/by-substitution.cc b/src/pyhpp/constraints/by-substitution.cc index 55a7d882..fa9fa439 100644 --- a/src/pyhpp/constraints/by-substitution.cc +++ b/src/pyhpp/constraints/by-substitution.cc @@ -31,7 +31,7 @@ #include #include -// DocNamespace(hpp::constraints) +// DocNamespace(hpp::constraints::solver) using namespace boost::python; @@ -54,7 +54,7 @@ void exposeBySubstitution() { .value("INFEASIBLE", HierarchicalIterative::INFEASIBLE) .value("SUCCESS", HierarchicalIterative::SUCCESS); - // DocClass(solver::BySubstitution) + // DocClass(BySubstitution) class_ >( "BySubstitution", init()) .def("explicitConstraintSetHasChanged", diff --git a/src/pyhpp/constraints/explicit.cc b/src/pyhpp/constraints/explicit.cc index 4b076f8d..fe6c9cfb 100644 --- a/src/pyhpp/constraints/explicit.cc +++ b/src/pyhpp/constraints/explicit.cc @@ -31,6 +31,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -61,6 +63,7 @@ ExplicitPtr_t createExplicit(const LiegroupSpacePtr_t& configSpace, } void exposeExplicit() { + // DocClass(Explicit) class_("Explicit", no_init) .def("create", &createExplicit) .staticmethod("create"); diff --git a/src/pyhpp/constraints/generic-transformation.cc b/src/pyhpp/constraints/generic-transformation.cc index a4be2f8a..425c0dfd 100644 --- a/src/pyhpp/constraints/generic-transformation.cc +++ b/src/pyhpp/constraints/generic-transformation.cc @@ -31,6 +31,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { diff --git a/src/pyhpp/constraints/implicit.cc b/src/pyhpp/constraints/implicit.cc index 72aba304..a5cd89c0 100644 --- a/src/pyhpp/constraints/implicit.cc +++ b/src/pyhpp/constraints/implicit.cc @@ -61,7 +61,7 @@ void exposeImplicit() { .def("comparisonType", static_cast( &Implicit::comparisonType), - return_internal_reference<>()) + return_internal_reference<>(), DocClassMethod(comparisonType)) .def("comparisonType", static_cast( &Implicit::comparisonType)) diff --git a/src/pyhpp/constraints/locked-joint.cc b/src/pyhpp/constraints/locked-joint.cc index 450ae864..7cd14c13 100644 --- a/src/pyhpp/constraints/locked-joint.cc +++ b/src/pyhpp/constraints/locked-joint.cc @@ -25,6 +25,8 @@ #include #include +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { diff --git a/src/pyhpp/constraints/relative-com.cc b/src/pyhpp/constraints/relative-com.cc index 44b003a8..5672a0c8 100644 --- a/src/pyhpp/constraints/relative-com.cc +++ b/src/pyhpp/constraints/relative-com.cc @@ -32,6 +32,9 @@ #include #include #include + +// DocNamespace(hpp::constraints) + using namespace boost::python; namespace pyhpp { @@ -64,9 +67,10 @@ static RelativeComPtr_t create3(const std::string& name, } void exposeRelativeCom() { + // DocClass(RelativeCom) class_, boost::noncopyable>("RelativeCom", no_init) - .def("create", &create1) + .def("create", &create1, DocClassMethod(create)) .def("create", &create2) .def("create", &create3) .staticmethod("create"); diff --git a/src/pyhpp/core/config-validation.cc b/src/pyhpp/core/config-validation.cc index 9c0bf84f..6f2c1a8c 100644 --- a/src/pyhpp/core/config-validation.cc +++ b/src/pyhpp/core/config-validation.cc @@ -69,7 +69,7 @@ void exposeConfigValidation() { .PYHPP_DEFINE_METHOD2(ConfigValidations, add, DocClassMethod(add)) .PYHPP_DEFINE_METHOD2(ConfigValidations, numberConfigValidations, DocClassMethod(numberConfigValidations)) - .PYHPP_DEFINE_METHOD2(ConfigValidations, clear, DocClassMethod(clear)); + .def("clear", &ConfigValidations::clear); } } // namespace core } // namespace pyhpp diff --git a/src/pyhpp/core/configuration-shooter.cc b/src/pyhpp/core/configuration-shooter.cc index 36d0c39d..a6807200 100644 --- a/src/pyhpp/core/configuration-shooter.cc +++ b/src/pyhpp/core/configuration-shooter.cc @@ -32,6 +32,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -43,9 +45,10 @@ struct CSWrapper { }; void exposeConfigurationShooter() { + // DocClass(ConfigurationShooter) class_( "ConfigurationShooter", no_init) - .def("shoot", &CSWrapper::shoot); + .def("shoot", &CSWrapper::shoot, DocClassMethod(shoot)); } } // namespace core } // namespace pyhpp diff --git a/src/pyhpp/core/connected-component.cc b/src/pyhpp/core/connected-component.cc index 8bc8ee40..399b5e13 100644 --- a/src/pyhpp/core/connected-component.cc +++ b/src/pyhpp/core/connected-component.cc @@ -35,6 +35,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -73,11 +75,13 @@ struct CCWrapper { } }; void exposeConnectedComponent() { + // DocClass(ConnectedComponent) class_( "ConnectedComponent", no_init) - .def("nodes", &CCWrapper::nodes) - .def("reachableFrom", &CCWrapper::reachableFrom) - .def("reachableTo", &CCWrapper::reachableTo) + .def("nodes", &CCWrapper::nodes, DocClassMethod(nodes)) + .def("reachableFrom", &CCWrapper::reachableFrom, + DocClassMethod(reachableFrom)) + .def("reachableTo", &CCWrapper::reachableTo, DocClassMethod(reachableTo)) .def("__eq__", &CCWrapper::equality); } } // namespace core diff --git a/src/pyhpp/core/distance.cc b/src/pyhpp/core/distance.cc index aa6ac92e..a96f3f40 100644 --- a/src/pyhpp/core/distance.cc +++ b/src/pyhpp/core/distance.cc @@ -33,6 +33,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -55,8 +57,11 @@ struct DistanceWrapper { }; void exposeDistance() { + // DocClass(Distance) class_("Distance", no_init) - .def("compute", &DistanceWrapper::compute); + .def("compute", &DistanceWrapper::compute, DocClassMethod(compute)); + + // DocClass(WeighedDistance) class_, WeighedDistancePtr_t, boost::noncopyable>("WeighedDistance", no_init) .def("__init__", make_constructor(&WeighedDistance::create)) diff --git a/src/pyhpp/core/parameter.cc b/src/pyhpp/core/parameter.cc index 530c524a..36dc3a46 100644 --- a/src/pyhpp/core/parameter.cc +++ b/src/pyhpp/core/parameter.cc @@ -31,6 +31,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -80,6 +82,7 @@ Parameter create(object param) { Parameter createBool(bool param) { return Parameter(param); } void exposeParameter() { + // DocClass(Parameter) class_("Parameter", no_init) .def("create", &create) .staticmethod("create") diff --git a/src/pyhpp/core/path-optimizer.cc b/src/pyhpp/core/path-optimizer.cc index 1c153d49..1eac091a 100644 --- a/src/pyhpp/core/path-optimizer.cc +++ b/src/pyhpp/core/path-optimizer.cc @@ -40,6 +40,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -47,13 +49,15 @@ namespace core { using namespace hpp::core; void exposePathOptimizer() { + // DocClass(PathOptimizer) class_("PathOptimizer", no_init) - .def("problem", &PathOptimizer::problem) - .def("optimize", &PathOptimizer::optimize) - .def("interrupt", &PathOptimizer::interrupt) - .def("maxIterations", &PathOptimizer::maxIterations) - .def("timeOut", &PathOptimizer::timeOut); + .def("problem", &PathOptimizer::problem, DocClassMethod(problem)) + .def("optimize", &PathOptimizer::optimize, DocClassMethod(optimize)) + .def("interrupt", &PathOptimizer::interrupt, DocClassMethod(interrupt)) + .def("maxIterations", &PathOptimizer::maxIterations, + DocClassMethod(maxIterations)) + .def("timeOut", &PathOptimizer::timeOut, DocClassMethod(timeOut)); class_, diff --git a/src/pyhpp/core/path-planner.cc b/src/pyhpp/core/path-planner.cc index c09e37bb..124391d4 100644 --- a/src/pyhpp/core/path-planner.cc +++ b/src/pyhpp/core/path-planner.cc @@ -39,6 +39,8 @@ #include #include +// DocNamespace(hpp::core) + namespace pyhpp { namespace core { @@ -142,20 +144,32 @@ void PathPlanner::stopWhenProblemIsSolved(bool enable) { PathVectorPtr_t PathPlanner::computePath() const { return obj->computePath(); } void exposePathPlanner() { + // DocClass(PathPlanner) class_("PathPlanner", no_init) - .PYHPP_DEFINE_METHOD_CONST_REF(PathPlanner, roadmap) - .PYHPP_DEFINE_METHOD(PathPlanner, problem) - .PYHPP_DEFINE_METHOD(PathPlanner, startSolve) - .PYHPP_DEFINE_METHOD(PathPlanner, solve) - .PYHPP_DEFINE_METHOD(PathPlanner, tryConnectInitAndGoals) - .PYHPP_DEFINE_METHOD(PathPlanner, oneStep) - .PYHPP_DEFINE_METHOD(PathPlanner, finishSolve) - .PYHPP_DEFINE_METHOD(PathPlanner, interrupt) - .PYHPP_DEFINE_GETTER_SETTER_CONST_REF(PathPlanner, maxIterations, - unsigned long int) - .PYHPP_DEFINE_GETTER_SETTER_CONST_REF(PathPlanner, timeOut, double) - .PYHPP_DEFINE_METHOD(PathPlanner, stopWhenProblemIsSolved) - .PYHPP_DEFINE_METHOD(PathPlanner, computePath); + .def("roadmap", &PathPlanner::roadmap, + return_value_policy(), DocClassMethod(roadmap)) + .def("problem", &PathPlanner::problem, DocClassMethod(problem)) + .def("startSolve", &PathPlanner::startSolve, DocClassMethod(startSolve)) + .def("solve", &PathPlanner::solve, DocClassMethod(solve)) + .def("tryConnectInitAndGoals", &PathPlanner::tryConnectInitAndGoals, + DocClassMethod(tryConnectInitAndGoals)) + .def("oneStep", &PathPlanner::oneStep, DocClassMethod(oneStep)) + .def("finishSolve", &PathPlanner::finishSolve, DocClassMethod(finishSolve)) + .def("interrupt", &PathPlanner::interrupt, DocClassMethod(interrupt)) + .def("maxIterations", + static_cast( + &PathPlanner::maxIterations)) + .def("maxIterations", + static_cast( + &PathPlanner::maxIterations)) + .def("timeOut", + static_cast(&PathPlanner::timeOut)) + .def("timeOut", + static_cast( + &PathPlanner::timeOut)) + .def("stopWhenProblemIsSolved", &PathPlanner::stopWhenProblemIsSolved, + DocClassMethod(stopWhenProblemIsSolved)) + .def("computePath", &PathPlanner::computePath, DocClassMethod(computePath)); pyhpp::core::pathPlanner::exposePathPlanners(); } diff --git a/src/pyhpp/core/path-projector.cc b/src/pyhpp/core/path-projector.cc index cac3bf01..c6678db2 100644 --- a/src/pyhpp/core/path-projector.cc +++ b/src/pyhpp/core/path-projector.cc @@ -36,6 +36,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -56,9 +58,10 @@ struct PPWrapper { }; void exposePathProjector() { + // DocClass(PathProjector) class_("PathProjector", no_init) - .def("apply", &PPWrapper::apply) + .def("apply", &PPWrapper::apply, DocClassMethod(apply)) .def("apply", &PPWrapper::py_apply); class_, diff --git a/src/pyhpp/core/path-validation.cc b/src/pyhpp/core/path-validation.cc index 22988828..b46db98e 100644 --- a/src/pyhpp/core/path-validation.cc +++ b/src/pyhpp/core/path-validation.cc @@ -40,6 +40,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -79,9 +81,10 @@ struct PVWrapper { }; void exposePathValidation() { + // DocClass(PathValidation) class_( "PathValidation", no_init) - .def("validate", &PVWrapper::validate) + .def("validate", &PVWrapper::validate, DocClassMethod(validate)) .def("validate", &PVWrapper::py_validate) .def("validateConfiguration", &PVWrapper::validateConfiguration); diff --git a/src/pyhpp/core/path/spline.cc b/src/pyhpp/core/path/spline.cc index 2f6e69b3..5b7b0759 100644 --- a/src/pyhpp/core/path/spline.cc +++ b/src/pyhpp/core/path/spline.cc @@ -34,6 +34,8 @@ #include #include +// DocNamespace(hpp::core::path) + using namespace boost::python; namespace pyhpp { diff --git a/src/pyhpp/core/path/vector.cc b/src/pyhpp/core/path/vector.cc index 6388da39..fde83e71 100644 --- a/src/pyhpp/core/path/vector.cc +++ b/src/pyhpp/core/path/vector.cc @@ -34,6 +34,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -42,17 +44,19 @@ namespace path { using namespace hpp::core; void exposeVector() { + // DocClass(PathVector) class_, boost::noncopyable>("Vector", no_init) .def("create", static_cast( - &PathVector::create)) + &PathVector::create), + DocClassMethod(create)) .staticmethod("create") - .PYHPP_DEFINE_METHOD(PathVector, numberPaths) - .PYHPP_DEFINE_METHOD(PathVector, pathAtRank) - .PYHPP_DEFINE_METHOD(PathVector, rankAtParam) - .PYHPP_DEFINE_METHOD(PathVector, appendPath) - .PYHPP_DEFINE_METHOD(PathVector, concatenate) - .PYHPP_DEFINE_METHOD(PathVector, flatten); + .def("numberPaths", &PathVector::numberPaths, DocClassMethod(numberPaths)) + .def("pathAtRank", &PathVector::pathAtRank, DocClassMethod(pathAtRank)) + .def("rankAtParam", &PathVector::rankAtParam, DocClassMethod(rankAtParam)) + .def("appendPath", &PathVector::appendPath, DocClassMethod(appendPath)) + .def("concatenate", &PathVector::concatenate, DocClassMethod(concatenate)) + .def("flatten", &PathVector::flatten, DocClassMethod(flatten)); class_("Vectors").def( vector_indexing_suite()); diff --git a/src/pyhpp/core/problem-target.cc b/src/pyhpp/core/problem-target.cc index 4b514d69..8256081a 100644 --- a/src/pyhpp/core/problem-target.cc +++ b/src/pyhpp/core/problem-target.cc @@ -31,6 +31,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -39,6 +41,7 @@ namespace core { using namespace hpp::core; void exposeProblemTarget() { + // DocClass(ProblemTarget) class_("ProblemTarget", no_init) diff --git a/src/pyhpp/core/problem.cc b/src/pyhpp/core/problem.cc index a8376220..5d9eca3a 100644 --- a/src/pyhpp/core/problem.cc +++ b/src/pyhpp/core/problem.cc @@ -30,6 +30,8 @@ #include "pyhpp/core/problem.hh" +// DocNamespace(hpp::core) + #include #include #include @@ -593,12 +595,16 @@ void register_problem_converters() { void exposeProblem() { class_("CppCoreProblem", no_init); + // DocClass(Problem) class_("Problem", init()) - .PYHPP_DEFINE_METHOD_CONST_REF_BY_VALUE(Problem, robot) - .PYHPP_DEFINE_METHOD(Problem, setParameter) + .def("robot", &Problem::robot, return_value_policy(), + DocClassMethod(robot)) + .def("setParameter", &Problem::setParameter, DocClassMethod(setParameter)) .def("setParameter", &Problem::setParameterFloat) .def("setParameter", &Problem::setParameterInt) - .PYHPP_DEFINE_METHOD_CONST_REF_BY_VALUE(Problem, getParameter) + .def("getParameter", &Problem::getParameter, + return_value_policy(), + DocClassMethod(getParameter)) .def("steeringMethod", static_cast( &Problem::steeringMethod)) @@ -613,8 +619,10 @@ void exposeProblem() { static_cast(&Problem::configValidation), (arg("configValidation"))) - .def("addConfigValidation", &Problem::addConfigValidation) - .def("clearConfigValidations", &Problem::clearConfigValidations) + .def("addConfigValidation", &Problem::addConfigValidation, + DocClassMethod(addConfigValidation)) + .def("clearConfigValidations", &Problem::clearConfigValidations, + DocClassMethod(clearConfigValidations)) .def("pathValidation", static_cast(&Problem::pathValidation)) @@ -640,9 +648,11 @@ void exposeProblem() { .def("configurationShooter", static_cast(&Problem::configurationShooter), (arg("configurationShooter"))) - .PYHPP_DEFINE_METHOD(Problem, initConfig) - .PYHPP_DEFINE_METHOD(Problem, addGoalConfig) - .PYHPP_DEFINE_METHOD(Problem, resetGoalConfigs) + .def("initConfig", &Problem::initConfig, DocClassMethod(initConfig)) + .def("addGoalConfig", &Problem::addGoalConfig, + DocClassMethod(addGoalConfig)) + .def("resetGoalConfigs", &Problem::resetGoalConfigs, + DocClassMethod(resetGoalConfigs)) .PYHPP_DEFINE_METHOD(Problem, addPartialCom) .PYHPP_DEFINE_METHOD(Problem, getPartialCom) .PYHPP_DEFINE_METHOD(Problem, createRelativeComConstraint) diff --git a/src/pyhpp/core/reports.cc b/src/pyhpp/core/reports.cc index 8ee49c50..b12e1a42 100644 --- a/src/pyhpp/core/reports.cc +++ b/src/pyhpp/core/reports.cc @@ -37,6 +37,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { @@ -44,16 +46,19 @@ namespace core { using namespace hpp::core; void exposeReports() { + // DocClass(ValidationReport) class_( "ValidationReport", no_init) .def("__str__", &to_str); + // DocClass(CollisionValidationReport) class_ >("CollisionValidationReport", no_init) .def_readonly("object1", &CollisionValidationReport::object1) .def_readonly("object2", &CollisionValidationReport::object2) .def_readonly("result", &CollisionValidationReport::result); + // DocClass(JointBoundValidationReport) class_ >("JointBoundValidationReport", no_init) .def_readonly("joint_", &JointBoundValidationReport::joint_) @@ -62,12 +67,14 @@ void exposeReports() { .def_readonly("upperBound_", &JointBoundValidationReport::upperBound_) .def_readonly("value_", &JointBoundValidationReport::value_); + // DocClass(PathValidationReport) class_ >("PathValidationReport", no_init) .def_readwrite("parameter", &PathValidationReport::parameter) .def_readwrite("configurationReport", &PathValidationReport::configurationReport); + // DocClass(CollisionPathValidationReport) class_ >("CollisionPathValidationReport", no_init) diff --git a/src/pyhpp/core/steering-method.cc b/src/pyhpp/core/steering-method.cc index 8f46935b..e2e3532d 100644 --- a/src/pyhpp/core/steering-method.cc +++ b/src/pyhpp/core/steering-method.cc @@ -39,6 +39,8 @@ #include #include +// DocNamespace(hpp::core) + namespace pyhpp { namespace core { @@ -140,13 +142,15 @@ const ConstraintSetPtr_t& SteeringMethod::constraints() const { void exposeSteeringMethod() { register_ptr_to_python>(); + // DocClass(SteeringMethod) class_("SteeringMethod", no_init) .def("__call__", &SteeringMethod::operator()) - .def("steer", &SteeringMethod::steer) - .def("problem", &SteeringMethod::problem) + .def("steer", &SteeringMethod::steer, DocClassMethod(steer)) + .def("problem", &SteeringMethod::problem, DocClassMethod(problem)) .def("constraints", static_cast( - &SteeringMethod::constraints)) + &SteeringMethod::constraints), + DocClassMethod(constraints)) .def("constraints", static_cast( &SteeringMethod::constraints), diff --git a/src/pyhpp/manipulation/device.cc b/src/pyhpp/manipulation/device.cc index f414bf93..a68b273f 100644 --- a/src/pyhpp/manipulation/device.cc +++ b/src/pyhpp/manipulation/device.cc @@ -32,6 +32,8 @@ #include #include +// DocNamespace(hpp::manipulation) + namespace pyhpp { namespace manipulation { using namespace boost::python; @@ -146,8 +148,9 @@ void setHandleMaskComp(const HandlePtr_t& handle, } void exposeHandle() { + // DocClass(Handle) class_("Handle", no_init) - .def("create", &Handle::create) + .def("create", &Handle::create, DocClassMethod(create)) .staticmethod("create") .add_property("name", &getHandleName, &setHandleName) .add_property("localPosition", &getHandleLocalPosition, @@ -158,15 +161,19 @@ void exposeHandle() { "clearance", static_cast(&Handle::clearance), static_cast(&Handle::clearance)) - .def("createGrasp", &Handle::createGrasp) - .def("createPreGrasp", &Handle::createPreGrasp) - .def("createGraspComplement", &Handle::createGraspComplement) - .def("createGraspAndComplement", &Handle::createGraspAndComplement); + .def("createGrasp", &Handle::createGrasp, DocClassMethod(createGrasp)) + .def("createPreGrasp", &Handle::createPreGrasp, + DocClassMethod(createPreGrasp)) + .def("createGraspComplement", &Handle::createGraspComplement, + DocClassMethod(createGraspComplement)) + .def("createGraspAndComplement", &Handle::createGraspAndComplement, + DocClassMethod(createGraspAndComplement)); class_ >("HandleMap") .def(boost::python::map_indexing_suite, true>()); } void exposeDevice() { + // DocClass(Device) class_, boost::shared_ptr, boost::noncopyable>("Device", init()) .def("setRobotRootPosition", &Device::setRobotRootPosition) diff --git a/src/pyhpp/manipulation/graph.cc b/src/pyhpp/manipulation/graph.cc index 0337bcb5..427575d3 100644 --- a/src/pyhpp/manipulation/graph.cc +++ b/src/pyhpp/manipulation/graph.cc @@ -46,6 +46,8 @@ #include "hpp/manipulation/constraint-set.hh" #include "pyhpp/core/problem.hh" +// DocNamespace(hpp::manipulation::graph) + namespace { const char* DOC_CREATESTATE = @@ -1236,13 +1238,17 @@ PyObject* getGraphCapsule(const PyWGraph& self) { using namespace boost::python; void exposeGraph() { + // DocClass(State) class_("State", no_init) - .def("name", &PyWState::name); + .def("name", &PyWState::name, DocClassMethod(name)); + // DocClass(Edge) class_("Transition", no_init) - .def("name", &PyWEdge::name) - .def("pathValidation", &PyWEdge::pathValidation); + .def("name", &PyWEdge::name, DocClassMethod(name)) + .def("pathValidation", &PyWEdge::pathValidation, + DocClassMethod(pathValidation)); + // DocClass(Graph) class_( "Graph", init()) diff --git a/src/pyhpp/manipulation/path-optimizer.cc b/src/pyhpp/manipulation/path-optimizer.cc index 5a761361..79df1863 100644 --- a/src/pyhpp/manipulation/path-optimizer.cc +++ b/src/pyhpp/manipulation/path-optimizer.cc @@ -37,6 +37,8 @@ #include #include +// DocNamespace(hpp::manipulation) + using namespace boost::python; namespace pyhpp { diff --git a/src/pyhpp/manipulation/path-planner.cc b/src/pyhpp/manipulation/path-planner.cc index 382f9eff..fd5720e8 100644 --- a/src/pyhpp/manipulation/path-planner.cc +++ b/src/pyhpp/manipulation/path-planner.cc @@ -38,6 +38,8 @@ #include #include +// DocNamespace(hpp::manipulation::pathPlanner) + namespace pyhpp { namespace manipulation { @@ -227,6 +229,7 @@ bool EndEffectorTrajectory::checkFeasibilityOnly() const { // } void exposePathPlanners() { + // DocClass(TransitionPlanner) boost::python::class_>( "TransitionPlanner", boost::python::init()) @@ -236,21 +239,25 @@ void exposePathPlanners() { .def("innerPlanner", static_cast( &TransitionPlanner::innerPlanner)) - .def("innerProblem", &TransitionPlanner::innerProblem) - .def("planPath", &TransitionPlanner::planPath) + .def("innerProblem", &TransitionPlanner::innerProblem, + DocClassMethod(innerProblem)) + .def("planPath", &TransitionPlanner::planPath, DocClassMethod(planPath)) .def("directPath", &TransitionPlanner::directPath) .def("validateConfiguration", &TransitionPlanner::validateConfiguration) - .def("optimizePath", &TransitionPlanner::optimizePath) - .def("timeParameterization", &TransitionPlanner::timeParameterization) - .def("setEdge", &TransitionPlanner::setEdge) + .def("optimizePath", &TransitionPlanner::optimizePath, + DocClassMethod(optimizePath)) + .def("timeParameterization", &TransitionPlanner::timeParameterization, + DocClassMethod(timeParameterization)) + .def("setEdge", &TransitionPlanner::setEdge, DocClassMethod(setEdge)) .def("setReedsAndSheppSteeringMethod", - &TransitionPlanner::setReedsAndSheppSteeringMethod) - .def("pathProjector", &TransitionPlanner::pathProjector) - .def("clearPathOptimizers", &TransitionPlanner::clearPathOptimizers) + &TransitionPlanner::setReedsAndSheppSteeringMethod, + DocClassMethod(setReedsAndSheppSteeringMethod)) + .def("pathProjector", &TransitionPlanner::pathProjector, + DocClassMethod(pathProjector)) + .def("clearPathOptimizers", &TransitionPlanner::clearPathOptimizers, + DocClassMethod(clearPathOptimizers)) .def("addPathOptimizer", &TransitionPlanner::addPathOptimizer, - "Add a path optimizer\n\n Note: the input path optimizer should " - "have been constructed" - " with\n the inner problem of this class."); + DocClassMethod(addPathOptimizer)); boost::python::class_>( @@ -261,6 +268,7 @@ void exposePathPlanners() { boost::python::bases>( "StatesPathFinder", boost::python::init()); + // DocClass(EndEffectorTrajectory) boost::python::class_>( "EndEffectorTrajectory", diff --git a/src/pyhpp/manipulation/path-projector.cc b/src/pyhpp/manipulation/path-projector.cc index f420d24e..61b92bb7 100644 --- a/src/pyhpp/manipulation/path-projector.cc +++ b/src/pyhpp/manipulation/path-projector.cc @@ -39,6 +39,8 @@ #include #include +// DocNamespace(hpp::core) + using namespace boost::python; namespace pyhpp { diff --git a/src/pyhpp/manipulation/problem.cc b/src/pyhpp/manipulation/problem.cc index 30b609a2..30582044 100644 --- a/src/pyhpp/manipulation/problem.cc +++ b/src/pyhpp/manipulation/problem.cc @@ -39,6 +39,8 @@ #include #include +// DocNamespace(hpp::manipulation) + using namespace boost::python; namespace pyhpp { @@ -121,11 +123,12 @@ void Problem::graphSteeringMethod( // } void exposeProblem() { + // DocClass(Problem) class_>("Problem", init()) .PYHPP_DEFINE_GETTER_SETTER_CONST_REF(Problem, constraintGraph, PyWGraphPtr_t) - .PYHPP_DEFINE_METHOD(Problem, checkProblem) + .def("checkProblem", &Problem::checkProblem, DocClassMethod(checkProblem)) .def( "steeringMethod", static_cast( diff --git a/src/pyhpp/manipulation/steering-method.cc b/src/pyhpp/manipulation/steering-method.cc index bea7cab8..ecd88083 100644 --- a/src/pyhpp/manipulation/steering-method.cc +++ b/src/pyhpp/manipulation/steering-method.cc @@ -33,6 +33,8 @@ #include #include +// DocNamespace(hpp::manipulation) + namespace pyhpp { namespace manipulation { diff --git a/src/pyhpp/pinocchio/device.cc b/src/pyhpp/pinocchio/device.cc index 3e37f69e..b439402c 100644 --- a/src/pyhpp/pinocchio/device.cc +++ b/src/pyhpp/pinocchio/device.cc @@ -42,6 +42,8 @@ #include #include +// DocNamespace(hpp::pinocchio) + // #include // #include @@ -211,8 +213,9 @@ static boost::python::list getJointsPosition( } void exposeGripper() { + // DocClass(Gripper) class_("Gripper", no_init) - .def("create", &Gripper::create) + .def("create", &Gripper::create, DocClassMethod(create)) .staticmethod("create") .add_property("localPosition", &getObjectPositionInJoint) .add_property( @@ -295,30 +298,35 @@ void exposeDevice() { .value("COMPUTE_ALL", hpp::pinocchio::COMPUTE_ALL); void (Device::*cfk)(int) = &Device::computeForwardKinematics; + // DocClass(Device) class_, boost::noncopyable>("Device", no_init) .def("__init__", make_constructor(&createDevice)) - .def("name", &Device::name, return_value_policy()) + .def("name", &Device::name, return_value_policy(), + DocClassMethod(name)) .def("configSpace", &Device::configSpace, - return_value_policy()) + return_value_policy(), DocClassMethod(configSpace)) .def("model", &Device::model, return_internal_reference<>()) .def("data", &Device::data, return_internal_reference<>()) .def("geomData", &Device::geomData, return_internal_reference<>()) .def("geomModel", &Device::geomModel, return_internal_reference<>()) - .def("visualModel", &Device::visualModel, return_internal_reference<>()) - .PYHPP_DEFINE_METHOD(Device, configSize) - .PYHPP_DEFINE_METHOD(Device, numberDof) + .def("configSize", &Device::configSize, DocClassMethod(configSize)) + .def("numberDof", &Device::numberDof, DocClassMethod(numberDof)) .def("currentConfiguration", static_cast( &Device::currentConfiguration), - return_value_policy()) + return_value_policy(), + DocClassMethod(currentConfiguration)) .def("currentConfiguration", Device_currentConfiguration) - .def("computeForwardKinematics", cfk) + .def("computeForwardKinematics", cfk, + DocClassMethod(computeForwardKinematics)) .def("computeFramesForwardKinematics", - &Device::computeFramesForwardKinematics) - .def("updateGeometryPlacements", &Device::updateGeometryPlacements) + &Device::computeFramesForwardKinematics, + DocClassMethod(computeFramesForwardKinematics)) + .def("updateGeometryPlacements", &Device::updateGeometryPlacements, + DocClassMethod(updateGeometryPlacements)) .add_property("rankInConfiguration", &rankInConfiguration) .def("setJointBounds", &setJointBounds) .def("getCenterOfMass", &getCenterOfMass) diff --git a/src/pyhpp/pinocchio/liegroup.cc b/src/pyhpp/pinocchio/liegroup.cc index e51984e1..1c973878 100644 --- a/src/pyhpp/pinocchio/liegroup.cc +++ b/src/pyhpp/pinocchio/liegroup.cc @@ -36,6 +36,8 @@ #include #include +// DocNamespace(hpp::pinocchio) + using namespace boost::python; namespace pyhpp { @@ -154,39 +156,43 @@ struct LgERWrapper { }; void exposeLiegroup() { + // DocClass(LiegroupSpace) class_("LiegroupSpace", no_init) .def("__str__", &to_str_from_operator) - .def("name", &LiegroupSpace::name, return_value_policy()) - .PYHPP_DEFINE_METHOD(LiegroupSpace, Rn) + .def("name", &LiegroupSpace::name, return_value_policy(), + DocClassMethod(name)) + .def("Rn", &LiegroupSpace::Rn, DocClassMethod(Rn)) .staticmethod("Rn") - .PYHPP_DEFINE_METHOD(LiegroupSpace, R1) + .def("R1", &LiegroupSpace::R1, DocClassMethod(R1)) .staticmethod("R1") - .PYHPP_DEFINE_METHOD(LiegroupSpace, R2) + .def("R2", &LiegroupSpace::R2, DocClassMethod(R2)) .staticmethod("R2") - .PYHPP_DEFINE_METHOD(LiegroupSpace, R3) + .def("R3", &LiegroupSpace::R3, DocClassMethod(R3)) .staticmethod("R3") - .PYHPP_DEFINE_METHOD(LiegroupSpace, SE2) + .def("SE2", &LiegroupSpace::SE2, DocClassMethod(SE2)) .staticmethod("SE2") - .PYHPP_DEFINE_METHOD(LiegroupSpace, SE3) + .def("SE3", &LiegroupSpace::SE3, DocClassMethod(SE3)) .staticmethod("SE3") - .PYHPP_DEFINE_METHOD(LiegroupSpace, R2xSO2) + .def("R2xSO2", &LiegroupSpace::R2xSO2, DocClassMethod(R2xSO2)) .staticmethod("R2xSO2") - .PYHPP_DEFINE_METHOD(LiegroupSpace, R3xSO3) + .def("R3xSO3", &LiegroupSpace::R3xSO3, DocClassMethod(R3xSO3)) .staticmethod("R3xSO3") - .PYHPP_DEFINE_METHOD(LiegroupSpace, empty) + .def("empty", &LiegroupSpace::empty, DocClassMethod(empty)) .staticmethod("empty") - .PYHPP_DEFINE_METHOD(LiegroupSpace, mergeVectorSpaces) - .PYHPP_DEFINE_METHOD(LgSWrapper, dIntegrate_dq) - .PYHPP_DEFINE_METHOD(LgSWrapper, dIntegrate_dv) - .PYHPP_DEFINE_METHOD(LgSWrapper, dDifference_dq0) - .PYHPP_DEFINE_METHOD(LgSWrapper, dDifference_dq1) + .def("mergeVectorSpaces", &LiegroupSpace::mergeVectorSpaces, + DocClassMethod(mergeVectorSpaces)) + .def("dIntegrate_dq", &LgSWrapper::dIntegrate_dq) + .def("dIntegrate_dv", &LgSWrapper::dIntegrate_dv) + .def("dDifference_dq0", &LgSWrapper::dDifference_dq0) + .def("dDifference_dq1", &LgSWrapper::dDifference_dq1) .def(self == self) .def(self != self) // Operation on shared pointers... .def("__imul__", &LgSWrapper::itimes) .def("__mul__", &LgSWrapper::times); + // DocClass(LiegroupElement) class_("LiegroupElement", init()) .def(init()) @@ -199,12 +205,13 @@ void exposeLiegroup() { .def("vector", static_cast( &LiegroupElement::vector), - return_value_policy()) + return_value_policy(), DocClassMethod(vector)) .def("space", &LiegroupElement::space, - return_value_policy()) + return_value_policy(), DocClassMethod(space)) .def(self - self) .def(self + vector_t()); + // DocClass(LiegroupElementRef) class_("LiegroupElementRef", init()) // Pythonic API @@ -216,9 +223,9 @@ void exposeLiegroup() { .def("vector", static_cast( &LiegroupElementRef::vector), - return_value_policy()) + return_value_policy(), DocClassMethod(vector)) .def("space", &LiegroupElementRef::space, - return_value_policy()) + return_value_policy(), DocClassMethod(space)) .def(self - self) .def(self + vector_t()); } From afba5d2d5260116694b6e57da3c7b9f7bf2377aa Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 26 Jan 2026 08:49:36 +0000 Subject: [PATCH 3/3] [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci --- doc/doxygen_xml_parser.py | 4 +--- src/pyhpp/constraints/by-substitution.cc | 3 +-- src/pyhpp/core/constraint.cc | 20 ++++++++------------ src/pyhpp/core/path-planner.cc | 11 ++++++----- src/pyhpp/core/path/vector.cc | 5 +++-- src/pyhpp/core/problem.cc | 4 ++-- 6 files changed, 21 insertions(+), 26 deletions(-) diff --git a/doc/doxygen_xml_parser.py b/doc/doxygen_xml_parser.py index aa59cad5..c4aa0400 100644 --- a/doc/doxygen_xml_parser.py +++ b/doc/doxygen_xml_parser.py @@ -64,9 +64,7 @@ def _getMemberFromGroup(self, memberDefKind, name): def _getMemberFromInherited(self, memberDefKind, name): """Look for memberdef in base class XML via listofallmembers member refid.""" - members = self.compound.xpath( - "listofallmembers/member[name='" + name + "']" - ) + members = self.compound.xpath("listofallmembers/member[name='" + name + "']") if not members: return None member = members[0] diff --git a/src/pyhpp/constraints/by-substitution.cc b/src/pyhpp/constraints/by-substitution.cc index fa9fa439..6b2e3c92 100644 --- a/src/pyhpp/constraints/by-substitution.cc +++ b/src/pyhpp/constraints/by-substitution.cc @@ -64,8 +64,7 @@ void exposeBySubstitution() { .def("explicitConstraintSet", static_cast( &BySubstitution::explicitConstraintSet), - return_internal_reference<>(), - DocClassMethod(explicitConstraintSet)) + return_internal_reference<>(), DocClassMethod(explicitConstraintSet)) .add_property("errorThreshold", static_cast( &BySubstitution::errorThreshold), diff --git a/src/pyhpp/core/constraint.cc b/src/pyhpp/core/constraint.cc index 86fc8e13..4e76df84 100644 --- a/src/pyhpp/core/constraint.cc +++ b/src/pyhpp/core/constraint.cc @@ -115,18 +115,14 @@ void exposeConstraint() { &ConfigProjector::solver), return_internal_reference<>(), DocClassMethod(solver)) .def("add", &ConfigProjector::add, DocClassMethod(add)) - .def("lastIsOptional", - static_cast( - &ConfigProjector::lastIsOptional)) - .def("lastIsOptional", - static_cast( - &ConfigProjector::lastIsOptional)) - .def("maxIterations", - static_cast( - &ConfigProjector::maxIterations)) - .def("maxIterations", - static_cast( - &ConfigProjector::maxIterations)) + .def("lastIsOptional", static_cast( + &ConfigProjector::lastIsOptional)) + .def("lastIsOptional", static_cast( + &ConfigProjector::lastIsOptional)) + .def("maxIterations", static_cast( + &ConfigProjector::maxIterations)) + .def("maxIterations", static_cast( + &ConfigProjector::maxIterations)) .def("errorThreshold", static_cast( &ConfigProjector::errorThreshold)) diff --git a/src/pyhpp/core/path-planner.cc b/src/pyhpp/core/path-planner.cc index 124391d4..bf1e33c2 100644 --- a/src/pyhpp/core/path-planner.cc +++ b/src/pyhpp/core/path-planner.cc @@ -154,7 +154,8 @@ void exposePathPlanner() { .def("tryConnectInitAndGoals", &PathPlanner::tryConnectInitAndGoals, DocClassMethod(tryConnectInitAndGoals)) .def("oneStep", &PathPlanner::oneStep, DocClassMethod(oneStep)) - .def("finishSolve", &PathPlanner::finishSolve, DocClassMethod(finishSolve)) + .def("finishSolve", &PathPlanner::finishSolve, + DocClassMethod(finishSolve)) .def("interrupt", &PathPlanner::interrupt, DocClassMethod(interrupt)) .def("maxIterations", static_cast( @@ -164,12 +165,12 @@ void exposePathPlanner() { &PathPlanner::maxIterations)) .def("timeOut", static_cast(&PathPlanner::timeOut)) - .def("timeOut", - static_cast( - &PathPlanner::timeOut)) + .def("timeOut", static_cast( + &PathPlanner::timeOut)) .def("stopWhenProblemIsSolved", &PathPlanner::stopWhenProblemIsSolved, DocClassMethod(stopWhenProblemIsSolved)) - .def("computePath", &PathPlanner::computePath, DocClassMethod(computePath)); + .def("computePath", &PathPlanner::computePath, + DocClassMethod(computePath)); pyhpp::core::pathPlanner::exposePathPlanners(); } diff --git a/src/pyhpp/core/path/vector.cc b/src/pyhpp/core/path/vector.cc index dfe89104..d08b368e 100644 --- a/src/pyhpp/core/path/vector.cc +++ b/src/pyhpp/core/path/vector.cc @@ -75,8 +75,9 @@ void exposeVector() { // DocClass(PathVector) class_, boost::noncopyable>("Vector", no_init) - .def("create", static_cast( - &PathVector::create), + .def("create", + static_cast( + &PathVector::create), DocClassMethod(create)) .staticmethod("create") .def("numberPaths", &PathVector::numberPaths, DocClassMethod(numberPaths)) diff --git a/src/pyhpp/core/problem.cc b/src/pyhpp/core/problem.cc index 5d9eca3a..e6dcb0f8 100644 --- a/src/pyhpp/core/problem.cc +++ b/src/pyhpp/core/problem.cc @@ -597,8 +597,8 @@ void exposeProblem() { // DocClass(Problem) class_("Problem", init()) - .def("robot", &Problem::robot, return_value_policy(), - DocClassMethod(robot)) + .def("robot", &Problem::robot, + return_value_policy(), DocClassMethod(robot)) .def("setParameter", &Problem::setParameter, DocClassMethod(setParameter)) .def("setParameter", &Problem::setParameterFloat) .def("setParameter", &Problem::setParameterInt)