Skip to content

Commit

Permalink
Fixes for pybind11-stubgen errors (#6896)
Browse files Browse the repository at this point in the history
* Added open3d.core.Dtype.DtypeCode enum bindings.
* Changed TransformationEstimationPointToPoint.__repr__.
* Added __repr__ for Margins to provide nicer default values.
* Added TextureHandle binding.
* Improved __repr__ for SLACDebugOption and SLACOptimizerParams.
* Improved arguments with enum default values using py::arg_v.
* Fixed false tokens in GetArgumentTokens when docstring contains ",".
* Added type annotations to func signature output by ToGoogleDocString.
* Changed kdtree __repr__ methods to return proper constructor call.
* Fixed more __repr__ methods to return proper constructor calls.
* Replaced substr with resize to fix codacy issue.
* Define `capsule` as `Any` type to fix pybind11-stubgen error.
* Added `m` and `n` as TypeVars to fix stubgen when using Eigen::MatrixXd.
  • Loading branch information
timohl authored Dec 11, 2024
1 parent f2461a3 commit 601516a
Show file tree
Hide file tree
Showing 19 changed files with 166 additions and 96 deletions.
12 changes: 6 additions & 6 deletions cpp/pybind/camera/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,12 @@ void pybind_camera_definitions(py::module &m) {
"0, cx], [0, fy, "
"cy], [0, 0, 1]]``")
.def("__repr__", [](const PinholeCameraIntrinsic &c) {
return std::string("PinholeCameraIntrinsic with width = ") +
std::to_string(c.width_) +
std::string(" and height = ") +
std::to_string(c.height_) +
std::string(
".\nAccess intrinsics with intrinsic_matrix.");
return fmt::format(
"PinholeCameraIntrinsic("
"width={}, "
"height={}, "
")",
c.width_, c.height_);
});
docstring::ClassMethodDocInject(m_camera, "PinholeCameraIntrinsic",
"__init__");
Expand Down
7 changes: 7 additions & 0 deletions cpp/pybind/core/dtype.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,13 @@ namespace core {
void pybind_core_dtype_declarations(py::module &m) {
py::class_<Dtype, std::shared_ptr<Dtype>> dtype(m, "Dtype",
"Open3D data types.");
py::enum_<Dtype::DtypeCode>(dtype, "DtypeCode")
.value("Undefined", Dtype::DtypeCode::Undefined)
.value("Bool", Dtype::DtypeCode::Bool)
.value("Int", Dtype::DtypeCode::Int)
.value("UInt", Dtype::DtypeCode::UInt)
.value("Float", Dtype::DtypeCode::Float)
.value("Object", Dtype::DtypeCode::Object);
}
void pybind_core_dtype_definitions(py::module &m) {
// open3d.core.Dtype class
Expand Down
1 change: 1 addition & 0 deletions cpp/pybind/core/tensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,7 @@ void pybind_core_tensor_declarations(py::module& m) {
py::class_<Tensor> tensor(
m, "Tensor",
"A Tensor is a view of a data Blob with shape, stride, data_ptr.");
m.attr("capsule") = py::module_::import("typing").attr("Any");
}
void pybind_core_tensor_definitions(py::module& m) {
auto tensor = static_cast<py::class_<Tensor>>(m.attr("Tensor"));
Expand Down
27 changes: 19 additions & 8 deletions cpp/pybind/docstring.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,14 +201,24 @@ std::string FunctionDoc::ToGoogleDocString() const {
for (size_t i = 0; i < overload.argument_docs_.size(); ++i) {
const ArgumentDoc& argument_doc = overload.argument_docs_[i];
rc << argument_doc.name_;
if (argument_doc.type_ != "") {
rc << ": " << argument_doc.type_;
}
if (argument_doc.default_ != "") {
rc << "=" << argument_doc.default_;
rc << " = " << argument_doc.default_;
}
if (i != overload.argument_docs_.size() - 1) {
rc << ", ";
}
}
rc << ")" << std::endl;
rc << ")";

// Return type
if (overload.return_doc_.type_ != "") {
rc << " -> " << overload.return_doc_.type_;
}

rc << std::endl;

// Summary line, strictly speaking this shall be at the very front.
// However from a compiled Python module we need the function signature
Expand Down Expand Up @@ -347,6 +357,12 @@ std::vector<std::string> FunctionDoc::GetArgumentTokens(
str.replace(parenthesis_pos + 1, 0, ", ");
}

// Ignore everything after last argument (right before ") ->")
// Otherwise false argument matches might be found in docstrings
std::size_t arrow_pos = str.rfind(") -> ");
if (arrow_pos == std::string::npos) return {};
str.resize(arrow_pos);

// Get start positions
std::regex pattern("(, [A-Za-z_][A-Za-z\\d_]*:)");
std::smatch res;
Expand All @@ -366,12 +382,7 @@ std::vector<std::string> FunctionDoc::GetArgumentTokens(
for (size_t i = 0; i + 1 < argument_start_positions.size(); ++i) {
argument_end_positions.push_back(argument_start_positions[i + 1] - 2);
}
std::size_t arrow_pos = str.rfind(") -> ");
if (arrow_pos == std::string::npos) {
return {};
} else {
argument_end_positions.push_back(arrow_pos);
}
argument_end_positions.push_back(arrow_pos);

std::vector<std::string> argument_tokens;
for (size_t i = 0; i < argument_start_positions.size(); ++i) {
Expand Down
3 changes: 3 additions & 0 deletions cpp/pybind/geometry/geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@ void pybind_geometry_classes_declarations(py::module &m) {
std::shared_ptr<Geometry2D>, Geometry>
geometry2d(m, "Geometry2D",
"The base geometry class for 2D geometries.");

m.attr("m") = py::module_::import("typing").attr("TypeVar")("m");
m.attr("n") = py::module_::import("typing").attr("TypeVar")("n");
}
void pybind_geometry_classes_definitions(py::module &m) {
// open3d.geometry functions
Expand Down
26 changes: 13 additions & 13 deletions cpp/pybind/geometry/kdtreeflann.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,10 +58,10 @@ void pybind_kdtreeflann_definitions(py::module &m) {
kdtreesearchparam_knn.def(py::init<int>(), "knn"_a = 30)
.def("__repr__",
[](const KDTreeSearchParamKNN &param) {
return std::string(
"KDTreeSearchParamKNN with knn "
"= ") +
std::to_string(param.knn_);
return fmt::format(
"KDTreeSearchParamKNN("
"knn={})",
param.knn_);
})
.def_readwrite("knn", &KDTreeSearchParamKNN::knn_,
"Number of the neighbors that will be searched.");
Expand All @@ -73,10 +73,10 @@ void pybind_kdtreeflann_definitions(py::module &m) {
kdtreesearchparam_radius.def(py::init<double>(), "radius"_a)
.def("__repr__",
[](const KDTreeSearchParamRadius &param) {
return std::string(
"KDTreeSearchParamRadius with "
"radius = ") +
std::to_string(param.radius_);
return fmt::format(
"KDTreeSearchParamRadius("
"radius={})",
param.radius_);
})
.def_readwrite("radius", &KDTreeSearchParamRadius::radius_,
"Search radius.");
Expand All @@ -89,11 +89,11 @@ void pybind_kdtreeflann_definitions(py::module &m) {
.def(py::init<double, int>(), "radius"_a, "max_nn"_a)
.def("__repr__",
[](const KDTreeSearchParamHybrid &param) {
return std::string(
"KDTreeSearchParamHybrid with "
"radius = ") +
std::to_string(param.radius_) +
" and max_nn = " + std::to_string(param.max_nn_);
return fmt::format(
"KDTreeSearchParamHybrid("
"radius={}, "
"max_nn={})",
param.radius_, param.max_nn_);
})
.def_readwrite("radius", &KDTreeSearchParamHybrid::radius_,
"Search radius.")
Expand Down
21 changes: 15 additions & 6 deletions cpp/pybind/geometry/trianglemesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,15 +110,17 @@ void pybind_trianglemesh_definitions(py::module &m) {
":math:`v_o = v_i x strength (v_i * |N| - \\sum_{n \\in N} "
"v_n)`",
"number_of_iterations"_a = 1, "strength"_a = 1,
"filter_scope"_a = MeshBase::FilterScope::All)
py::arg_v("filter_scope", MeshBase::FilterScope::All,
"FilterScope.All"))
.def("filter_smooth_simple", &TriangleMesh::FilterSmoothSimple,
"Function to smooth triangle mesh with simple neighbour "
"average. :math:`v_o = \\frac{v_i + \\sum_{n \\in N} "
"v_n)}{|N| + 1}`, with :math:`v_i` being the input value, "
":math:`v_o` the output value, and :math:`N` is the set of "
"adjacent neighbours.",
"number_of_iterations"_a = 1,
"filter_scope"_a = MeshBase::FilterScope::All)
py::arg_v("filter_scope", MeshBase::FilterScope::All,
"FilterScope.All"))
.def("filter_smooth_laplacian",
&TriangleMesh::FilterSmoothLaplacian,
"Function to smooth triangle mesh using Laplacian. :math:`v_o "
Expand All @@ -129,7 +131,8 @@ void pybind_trianglemesh_definitions(py::module &m) {
"inverse distance (closer neighbours have higher weight), and "
"lambda_filter is the smoothing parameter.",
"number_of_iterations"_a = 1, "lambda_filter"_a = 0.5,
"filter_scope"_a = MeshBase::FilterScope::All)
py::arg_v("filter_scope", MeshBase::FilterScope::All,
"FilterScope.All"))
.def("filter_smooth_taubin", &TriangleMesh::FilterSmoothTaubin,
"Function to smooth triangle mesh using method of Taubin, "
"\"Curve and Surface Smoothing Without Shrinkage\", 1995. "
Expand All @@ -139,7 +142,9 @@ void pybind_trianglemesh_definitions(py::module &m) {
"parameter mu as smoothing parameter. This method avoids "
"shrinkage of the triangle mesh.",
"number_of_iterations"_a = 1, "lambda_filter"_a = 0.5,
"mu"_a = -0.53, "filter_scope"_a = MeshBase::FilterScope::All)
"mu"_a = -0.53,
py::arg_v("filter_scope", MeshBase::FilterScope::All,
"FilterScope.All"))
.def("has_vertices", &TriangleMesh::HasVertices,
"Returns ``True`` if the mesh contains vertices.")
.def("has_triangles", &TriangleMesh::HasTriangles,
Expand Down Expand Up @@ -250,7 +255,9 @@ void pybind_trianglemesh_definitions(py::module &m) {
&TriangleMesh::SimplifyVertexClustering,
"Function to simplify mesh using vertex clustering.",
"voxel_size"_a,
"contraction"_a = MeshBase::SimplificationContraction::Average)
py::arg_v("contraction",
MeshBase::SimplificationContraction::Average,
"SimplificationContraction.Average"))
.def("simplify_quadric_decimation",
&TriangleMesh::SimplifyQuadricDecimation,
"Function to simplify mesh using Quadric Error Metric "
Expand Down Expand Up @@ -298,7 +305,9 @@ void pybind_trianglemesh_definitions(py::module &m) {
"'As-Rigid-As-Possible Surface Modeling', 2007",
"constraint_vertex_indices"_a, "constraint_vertex_positions"_a,
"max_iter"_a,
"energy"_a = MeshBase::DeformAsRigidAsPossibleEnergy::Spokes,
py::arg_v("energy",
MeshBase::DeformAsRigidAsPossibleEnergy::Spokes,
"DeformAsRigidAsPossibleEnergy.Spokes"),
"smoothed_alpha"_a = 0.01)
.def_static(
"create_from_point_cloud_alpha_shape",
Expand Down
20 changes: 9 additions & 11 deletions cpp/pybind/pipelines/odometry/odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,17 +128,15 @@ void pybind_odometry_definitions(py::module &m) {
c.iteration_number_per_pyramid_level_[i]) +
", ";
str_iteration_number_per_pyramid_level_ += "] ";
return std::string("OdometryOption class.") +
/*std::string("\nodo_init = ") +
std::to_string(c.odo_init_) +*/
std::string("\niteration_number_per_pyramid_level = ") +
str_iteration_number_per_pyramid_level_ +
std::string("\ndepth_diff_max = ") +
std::to_string(c.depth_diff_max_) +
std::string("\ndepth_min = ") +
std::to_string(c.depth_min_) +
std::string("\ndepth_max = ") +
std::to_string(c.depth_max_);
return fmt::format(
"OdometryOption(\n"
"iteration_number_per_pyramid_level={},\n"
"depth_diff_max={},\n"
"depth_min={},\n"
"depth_max={},\n"
")",
str_iteration_number_per_pyramid_level_,
c.depth_diff_max_, c.depth_min_, c.depth_max_);
});

// open3d.odometry.RGBDOdometryJacobian
Expand Down
4 changes: 4 additions & 0 deletions cpp/pybind/pipelines/registration/feature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ void pybind_feature_declarations(py::module &m_registration) {
py::class_<Feature, std::shared_ptr<Feature>> feature(
m_registration, "Feature",
"Class to store featrues for registration.");
m_registration.attr("m") =
py::module_::import("typing").attr("TypeVar")("m");
m_registration.attr("n") =
py::module_::import("typing").attr("TypeVar")("n");
}
void pybind_feature_definitions(py::module &m_registration) {
// open3d.registration.Feature
Expand Down
67 changes: 35 additions & 32 deletions cpp/pybind/pipelines/registration/registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,9 +188,10 @@ void pybind_registration_definitions(py::module &m) {
"Maximum iteration before iteration stops.")
.def("__repr__", [](const ICPConvergenceCriteria &c) {
return fmt::format(
"ICPConvergenceCriteria class "
"with relative_fitness={:e}, relative_rmse={:e}, "
"and max_iteration={:d}",
"ICPConvergenceCriteria("
"relative_fitness={:e}, "
"relative_rmse={:e}, "
"max_iteration={:d})",
c.relative_fitness_, c.relative_rmse_,
c.max_iteration_);
});
Expand All @@ -214,9 +215,9 @@ void pybind_registration_definitions(py::module &m) {
"termination. Use 1.0 to avoid early termination.")
.def("__repr__", [](const RANSACConvergenceCriteria &c) {
return fmt::format(
"RANSACConvergenceCriteria "
"class with max_iteration={:d}, "
"and confidence={:e}",
"RANSACConvergenceCriteria("
"max_iteration={:d}, "
"confidence={:e})",
c.max_iteration_, c.confidence_);
});

Expand Down Expand Up @@ -264,11 +265,10 @@ void pybind_registration_definitions(py::module &m) {
"with_scaling"_a = false)
.def("__repr__",
[](const TransformationEstimationPointToPoint &te) {
return std::string(
"TransformationEstimationPointToPoint ") +
(te.with_scaling_
? std::string("with scaling.")
: std::string("without scaling."));
return fmt::format(
"TransformationEstimationPointToPoint("
"with_scaling={})",
te.with_scaling_ ? "True" : "False");
})
.def_readwrite(
"with_scaling",
Expand Down Expand Up @@ -336,10 +336,12 @@ Sets :math:`c = 1` if ``with_scaling`` is ``False``.
"kernel"_a)
.def("__repr__",
[](const TransformationEstimationForColoredICP &te) {
return std::string(
"TransformationEstimationForColoredICP ") +
("with lambda_geometric=" +
std::to_string(te.lambda_geometric_));
// This is missing kernel, but getting kernel name on C++
// is hard
return fmt::format(
"TransformationEstimationForColoredICP("
"lambda_geometric={})",
te.lambda_geometric_);
})
.def_readwrite(
"lambda_geometric",
Expand Down Expand Up @@ -380,10 +382,10 @@ Sets :math:`c = 1` if ``with_scaling`` is ``False``.
"kernel"_a)
.def("__repr__",
[](const TransformationEstimationForGeneralizedICP &te) {
return std::string(
"TransformationEstimationForGeneralizedICP"
" ") +
("with epsilon=" + std::to_string(te.epsilon_));
return fmt::format(
"TransformationEstimationForGeneralizedICP("
"epsilon={})",
te.epsilon_);
})
.def_readwrite("epsilon",
&TransformationEstimationForGeneralizedICP::epsilon_,
Expand Down Expand Up @@ -555,19 +557,20 @@ must hold true for all edges.)");
"tests on initial set of correspondences.")
.def("__repr__", [](const FastGlobalRegistrationOption &c) {
return fmt::format(
""
"FastGlobalRegistrationOption class "
"with \ndivision_factor={}"
"\nuse_absolute_scale={}"
"\ndecrease_mu={}"
"\nmaximum_correspondence_distance={}"
"\niteration_number={}"
"\ntuple_scale={}"
"\nmaximum_tuple_count={}",
"\ntuple_test={}", c.division_factor_,
c.use_absolute_scale_, c.decrease_mu_,
c.maximum_correspondence_distance_, c.iteration_number_,
c.tuple_scale_, c.maximum_tuple_count_, c.tuple_test_);
"FastGlobalRegistrationOption("
"\ndivision_factor={},"
"\nuse_absolute_scale={},"
"\ndecrease_mu={},"
"\nmaximum_correspondence_distance={},"
"\niteration_number={},"
"\ntuple_scale={},"
"\nmaximum_tuple_count={},"
"\ntuple_test={},"
"\n)",
c.division_factor_, c.use_absolute_scale_,
c.decrease_mu_, c.maximum_correspondence_distance_,
c.iteration_number_, c.tuple_scale_,
c.maximum_tuple_count_, c.tuple_test_);
});

// open3d.registration.RegistrationResult
Expand Down
3 changes: 2 additions & 1 deletion cpp/pybind/t/geometry/image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,8 @@ void pybind_image_definitions(py::module &m) {
"Upsample if sampling rate > 1. Aspect ratio is always "
"kept.",
"sampling_rate"_a = 0.5,
"interp_type"_a = Image::InterpType::Nearest)
py::arg_v("interp_type", Image::InterpType::Nearest,
"open3d.t.geometry.InterpType.Nearest"))
.def("pyrdown", &Image::PyrDown,
"Return a new downsampled image with pyramid downsampling "
"formed by a chained Gaussian filter (kernel_size = 5, sigma"
Expand Down
5 changes: 4 additions & 1 deletion cpp/pybind/t/geometry/lineset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,10 @@ transformation as :math:`P = R(P) + t`)");
line_set.def_static(
"create_camera_visualization", &LineSet::CreateCameraVisualization,
"view_width_px"_a, "view_height_px"_a, "intrinsic"_a, "extrinsic"_a,
"scale"_a = 1.f, "color"_a = core::Tensor({}, core::Float32),
"scale"_a = 1.f,
py::arg_v(
"color", core::Tensor({}, core::Float32),
"open3d.core.Tensor([], dtype=open3d.core.Dtype.Float32)"),
R"(Factory function to create a LineSet from intrinsic and extrinsic
matrices. Camera reference frame is shown with XYZ axes in RGB.
Expand Down
Loading

0 comments on commit 601516a

Please sign in to comment.