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..ee7ef79a 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,17 @@ 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..4e76df84 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,54 @@ 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/path/vector.cc b/src/pyhpp/core/path/vector.cc index 6388da39..d64d5ea2 100644 --- a/src/pyhpp/core/path/vector.cc +++ b/src/pyhpp/core/path/vector.cc @@ -29,10 +29,13 @@ #include #include +#include #include #include +#include #include #include +#include using namespace boost::python; @@ -41,6 +44,31 @@ namespace core { namespace path { using namespace hpp::core; +void savePathVector(PathVectorPtr_t pathVector, const std::string& filename) { + if (!pathVector) { + throw std::invalid_argument("Cannot save null PathVector"); + } + std::ofstream ofs(filename, std::ios::binary); + if (!ofs.is_open()) { + throw std::runtime_error("Failed to open file for writing: " + filename); + } + hpp::serialization::binary_oarchive ar(ofs); + ar.initialize(); + ar << hpp::serialization::make_nvp("pathVector", pathVector); +} + +PathVectorPtr_t loadPathVector(const std::string& filename) { + std::ifstream ifs(filename, std::ios::binary); + if (!ifs.is_open()) { + throw std::runtime_error("Failed to open file for reading: " + filename); + } + hpp::serialization::binary_iarchive ar(ifs); + ar.initialize(); + PathVectorPtr_t pathVector; + ar >> hpp::serialization::make_nvp("pathVector", pathVector); + return pathVector; +} + void exposeVector() { class_, boost::noncopyable>("Vector", no_init) @@ -52,7 +80,12 @@ void exposeVector() { .PYHPP_DEFINE_METHOD(PathVector, rankAtParam) .PYHPP_DEFINE_METHOD(PathVector, appendPath) .PYHPP_DEFINE_METHOD(PathVector, concatenate) - .PYHPP_DEFINE_METHOD(PathVector, flatten); + .PYHPP_DEFINE_METHOD(PathVector, flatten) + + // Serialization methods (binary format) + .def("save", &savePathVector, "Save PathVector to file (binary format)") + .def("load", &loadPathVector, "Load PathVector from file (binary format)") + .staticmethod("load"); class_("Vectors").def( vector_indexing_suite()); 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