Auto generate and deploy documentation (#71)

* show constructor docs

* constructor docs

* remove unnecessary dependencies for document generation

* trigger on tags
This commit is contained in:
koide3 2024-06-21 12:22:44 +09:00 committed by GitHub
parent be01905b04
commit f48faf0790
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
11 changed files with 437 additions and 119 deletions

38
.github/workflows/gendoc.yml vendored Normal file
View File

@ -0,0 +1,38 @@
name: gendoc
on:
push:
tags:
- '*'
# Allows you to run this workflow manually from the Actions tab
workflow_dispatch:
jobs:
gendoc:
name: Generate documentation
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v4
- name: Configure Git Credentials
run: |
git config user.name github-actions[bot]
git config user.email 41898282+github-actions[bot]@users.noreply.github.com
- name : Install dependencies
run: sudo apt-get install -y git cmake build-essential doxygen graphviz python3-dev python3-pip pybind11-dev libeigen3-dev libomp-dev python3-numpy python3-sphinx python3-sphinx-rtd-theme
- name: Install python dependencies
run: python -m pip install mkdocs mkdocs-material
- name: Generate documentation
run: cd docs && make all
- uses: actions/upload-artifact@v4
with:
name: site
path: ./site/*
- name: Deploy documentation
run: cd docs && make deploy

View File

@ -25,4 +25,4 @@ all: cpp py mkdocs
.PHONY: deploy
deploy:
@echo "Deploying documentation..."
cd .. && mkdocs gh-deploy
cd .. && mkdocs gh-deploy --force

View File

@ -9,6 +9,7 @@
project = 'small_gicp'
copyright = '2024, k.koide'
author = 'k.koide'
version = '0.1.1'
import os
import sys
@ -22,6 +23,7 @@ extensions = ['sphinx.ext.autodoc', 'sphinx.ext.napoleon']
templates_path = ['_templates']
exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']
autoclass_content = 'both'
# -- Options for HTML output -------------------------------------------------
# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output

View File

@ -22,10 +22,6 @@ markdown_extensions:
- pymdownx.inlinehilite
- pymdownx.snippets
- pymdownx.superfences
- pymdownx.emoji:
emoji_index: !!python/name:materialx.emoji.twemoji
emoji_generator: !!python/name:materialx.emoji.to_svg
- fontawesome_markdown
copyright: Copyright © 2024 Kenji Koide
extra:

View File

@ -99,11 +99,11 @@ void define_align(py::module& m) {
Parameters
----------
target_points : NDArray[np.float64]
target_points : numpy.ndarray[np.float64]
Nx3 or Nx4 matrix representing the target point cloud.
source_points : NDArray[np.float64]
source_points : numpy.ndarray[np.float64]
Nx3 or Nx4 matrix representing the source point cloud.
init_T_target_source : np.ndarray[np.float64]
init_T_target_source : numpy.ndarray[np.float64]
4x4 matrix representing the initial transformation from target to source.
registration_type : str = 'GICP'
Type of registration algorithm to use ('ICP', 'PLANE_ICP', 'GICP', 'VGICP').
@ -117,9 +117,10 @@ void define_align(py::module& m) {
Number of threads to use for parallel processing.
max_iterations : int = 20
Maximum number of iterations for the optimization algorithm.
Returns
-------
RegistrationResult
result : RegistrationResult
Object containing the final transformation matrix and convergence status.
)pbdoc");
@ -173,7 +174,7 @@ void define_align(py::module& m) {
Pointer to the source point cloud.
target_tree : KdTree<PointCloud>::ConstPtr, optional
Pointer to the KD-tree of the target for nearest neighbor search. If nullptr, a new tree is built.
init_T_target_source : NDArray[np.float64]
init_T_target_source : numpy.ndarray[np.float64]
4x4 matrix representing the initial transformation from target to source.
registration_type : str = 'GICP'
Type of registration algorithm to use ('ICP', 'PLANE_ICP', 'GICP').
@ -183,9 +184,10 @@ void define_align(py::module& m) {
Number of threads to use for computation.
max_iterations : int = 20
Maximum number of iterations for the optimization algorithm.
Returns
-------
RegistrationResult
result : RegistrationResult
Object containing the final transformation matrix and convergence status.
)pbdoc");
@ -221,7 +223,7 @@ void define_align(py::module& m) {
Voxel map constructed from the target point cloud.
source : PointCloud
Source point cloud to align to the target.
init_T_target_source : NDArray[np.float64]
init_T_target_source : numpy.ndarray[np.float64]
4x4 matrix representing the initial transformation from target to source.
max_correspondence_distance : float = 1.0
Maximum distance for corresponding point pairs.
@ -232,7 +234,7 @@ void define_align(py::module& m) {
Returns
-------
RegistrationResult
result : RegistrationResult
Object containing the final transformation matrix and convergence status.
)pbdoc");
}

View File

@ -22,7 +22,18 @@ void define_factors(py::module& m) {
// DistanceRejector
py::class_<DistanceRejector>(m, "DistanceRejector", "Correspondence rejection based on the distance between points.")
.def(py::init<>())
.def("set_max_distance", [](DistanceRejector& rejector, double dist) { rejector.max_dist_sq = dist * dist; }, py::arg("dist"), "Set the maximum distance.");
.def(
"set_max_distance",
[](DistanceRejector& rejector, double dist) { rejector.max_dist_sq = dist * dist; },
py::arg("dist"),
R"pbdoc(
Set maximum correspondence distance.
Parameters
----------
dist : float
Maximum correspondence distance.
)pbdoc");
// ICPFactor
py::class_<ICPFactor>(m, "ICPFactor", "ICP per-point factor")
@ -49,7 +60,35 @@ void define_factors(py::module& m) {
py::arg("T"),
py::arg("source_index"),
py::arg("rejector"),
"Linearize the factor. Returns a tuple of success, Hessian, gradient, and error.");
R"pbdoc(
Linearize the factor.
Parameters
----------
target : PointCloud
Target point cloud.
source : PointCloud
Source point cloud.
kdtree : KdTree
KdTree for the target point cloud.
T : numpy.ndarray
Transformation matrix. (4x4)
source_index : int
Index of the source point.
rejector : DistanceRejector
Correspondence rejector.
Returns
-------
success: bool
Success flag.
H : numpy.ndarray
Hessian matrix (6x6).
b : numpy.ndarray
Gradient vector (6,).
e : float
Error.
)pbdoc");
// PointToPlaneICPFactor
py::class_<PointToPlaneICPFactor>(m, "PointToPlaneICPFactor", "Point-to-plane ICP per-point factor")
@ -76,7 +115,35 @@ void define_factors(py::module& m) {
py::arg("T"),
py::arg("source_index"),
py::arg("rejector"),
"Linearize the factor. Returns a tuple of success, Hessian, gradient, and error.");
R"pbdoc(
Linearize the factor.
Parameters
----------
target : PointCloud
Target point cloud.
source : PointCloud
Source point cloud.
kdtree : KdTree
KdTree for the target point cloud.
T : numpy.ndarray
Transformation matrix. (4x4)
source_index : int
Index of the source point.
rejector : DistanceRejector
Correspondence rejector.
Returns
-------
success: bool
Success flag.
H : numpy.ndarray
Hessian matrix (6x6).
b : numpy.ndarray
Gradient vector (6,).
e : float
Error.
)pbdoc");
// GICPFactor
py::class_<GICPFactor>(m, "GICPFactor", "Generalized ICP per-point factor") //
@ -103,5 +170,33 @@ void define_factors(py::module& m) {
py::arg("T"),
py::arg("source_index"),
py::arg("rejector"),
"Linearize the factor. Returns a tuple of success, Hessian, gradient, and error.");
R"pbdoc(
Linearize the factor.
Parameters
----------
target : PointCloud
Target point cloud.
source : PointCloud
Source point cloud.
kdtree : KdTree
KdTree for the target point cloud.
T : numpy.ndarray
Transformation matrix. (4x4)
source_index : int
Index of the source point.
rejector : DistanceRejector
Correspondence rejector.
Returns
-------
success: bool
Success flag.
H : numpy.ndarray
Hessian matrix (6x6).
b : numpy.ndarray
Gradient vector (6,).
e : float
Error.
)pbdoc");
}

View File

@ -17,19 +17,51 @@ using namespace small_gicp;
void define_kdtree(py::module& m) {
// KdTree
py::class_<KdTree<PointCloud>, std::shared_ptr<KdTree<PointCloud>>>(m, "KdTree") //
.def(
py::init([](const Eigen::MatrixXd& points_numpy, int num_threads) {
if (points_numpy.cols() != 3 && points_numpy.cols() != 4) {
throw std::invalid_argument("points must have shape (n, 3) or (n, 4)");
}
auto points = std::make_shared<PointCloud>();
points->resize(points_numpy.rows());
for (int i = 0; i < points_numpy.rows(); i++) {
points->point(i) << points_numpy(i, 0), points_numpy(i, 1), points_numpy(i, 2), 1.0;
}
return std::make_shared<KdTree<PointCloud>>(points, KdTreeBuilderOMP(num_threads));
}),
py::arg("points"),
py::arg("num_threads") = 1,
R"""(
KdTree(points: numpy.ndarray, num_threads: int = 1)
Construct a KdTree from numpy.
Parameters
----------
points : numpy.ndarray, shape (n, 3) or (n, 4)
The input point cloud.
num_threads : int, optional
The number of threads to use for KdTree construction. Default is 1.
)""")
.def(
py::init([](const PointCloud::ConstPtr& points, int num_threads) { return std::make_shared<KdTree<PointCloud>>(points, KdTreeBuilderOMP(num_threads)); }),
py::arg("points"),
py::arg("num_threads") = 1,
R"""(
Construct a KdTree from a point cloud.
KdTree(points: PointCloud, num_threads: int = 1)
Parameters
----------
points : PointCloud
The input point cloud.
num_threads : int, optional
The number of threads to use for KdTree construction. Default is 1.
Construct a KdTree from a point cloud.
Parameters
----------
points : PointCloud
The input point cloud.
num_threads : int, optional
The number of threads to use for KdTree construction. Default is 1.
)""")
.def(
@ -42,21 +74,21 @@ void define_kdtree(py::module& m) {
},
py::arg("pt"),
R"""(
Find the nearest neighbor to a given point.
Find the nearest neighbor to a given point.
Parameters
----------
pt : NDArray, shape (3,)
The input point.
Parameters
----------
pt : numpy.ndarray, shape (3,)
The input point.
Returns
-------
found : int
Whether a neighbor was found (1 if found, 0 if not).
k_index : int
The index of the nearest neighbor in the point cloud.
k_sq_dist : float
The squared distance to the nearest neighbor.
Returns
-------
found : int
Whether a neighbor was found (1 if found, 0 if not).
k_index : int
The index of the nearest neighbor in the point cloud.
k_sq_dist : float
The squared distance to the nearest neighbor.
)""")
.def(
@ -70,21 +102,21 @@ void define_kdtree(py::module& m) {
py::arg("pt"),
py::arg("k"),
R"""(
Find the k nearest neighbors to a given point.
Find the k nearest neighbors to a given point.
Parameters
----------
pt : NDArray, shape (3,)
The input point.
k : int
The number of nearest neighbors to search for.
Parameters
----------
pt : numpy.ndarray, shape (3,)
The input point.
k : int
The number of nearest neighbors to search for.
Returns
-------
k_indices : NDArray, shape (k,)
The indices of the k nearest neighbors in the point cloud.
k_sq_dists : NDArray, shape (k,)
The squared distances to the k nearest neighbors.
Returns
-------
k_indices : numpy.ndarray, shape (k,)
The indices of the k nearest neighbors in the point cloud.
k_sq_dists : numpy.ndarray, shape (k,)
The squared distances to the k nearest neighbors.
)""")
.def(
@ -111,21 +143,21 @@ void define_kdtree(py::module& m) {
py::arg("pts"),
py::arg("num_threads") = 1,
R"""(
Find the nearest neighbors for a batch of points.
Find the nearest neighbors for a batch of points.
Parameters
----------
pts : NDArray, shape (n, 3) or (n, 4)
The input points.
num_threads : int, optional
The number of threads to use for the search. Default is 1.
Parameters
----------
pts : numpy.ndarray, shape (n, 3) or (n, 4)
The input points.
num_threads : int, optional
The number of threads to use for the search. Default is 1.
Returns
-------
k_indices : NDArray, shape (n,)
The indices of the nearest neighbors for each input point.
k_sq_dists : NDArray, shape (n,)
The squared distances to the nearest neighbors for each input point.
Returns
-------
k_indices : numpy.ndarray, shape (n,)
The indices of the nearest neighbors for each input point.
k_sq_dists : numpy.ndarray, shape (n,)
The squared distances to the nearest neighbors for each input point.
)""")
.def(
@ -155,22 +187,22 @@ void define_kdtree(py::module& m) {
py::arg("k"),
py::arg("num_threads") = 1,
R"""(
Find the k nearest neighbors for a batch of points.
Find the k nearest neighbors for a batch of points.
Parameters
----------
pts : NDArray, shape (n, 3) or (n, 4)
The input points.
k : int
The number of nearest neighbors to search for.
num_threads : int, optional
The number of threads to use for the search. Default is 1.
Parameters
----------
pts : numpy.ndarray, shape (n, 3) or (n, 4)
The input points.
k : int
The number of nearest neighbors to search for.
num_threads : int, optional
The number of threads to use for the search. Default is 1.
Returns
-------
k_indices : list of NDArray, shape (n,)
The list of indices of the k nearest neighbors for each input point.
k_sq_dists : list of NDArray, shape (n,)
The list of squared distances to the k nearest neighbors for each input point.
Returns
-------
k_indices : list of numpy.ndarray, shape (n,)
The list of indices of the k nearest neighbors for each input point.
k_sq_dists : list of numpy.ndarray, shape (n,)
The list of squared distances to the k nearest neighbors for each input point.
)""");
}

View File

@ -22,6 +22,6 @@ void define_misc(py::module& m) {
const auto points = read_ply(filename);
return std::make_shared<PointCloud>(points);
},
"Read PLY file",
"Read PLY file. This function can only read simple point clouds with XYZ properties for testing. Do not use this for general PLY IO.",
py::arg("filename"));
}

View File

@ -16,51 +16,144 @@ using namespace small_gicp;
void define_pointcloud(py::module& m) {
// PointCloud
py::class_<PointCloud, std::shared_ptr<PointCloud>>(m, "PointCloud") //
.def(py::init([](const Eigen::MatrixXd& points) {
if (points.cols() != 3 && points.cols() != 4) {
std::cerr << "points must be Nx3 or Nx4" << std::endl;
return std::make_shared<PointCloud>();
}
auto pc = std::make_shared<PointCloud>();
pc->resize(points.rows());
if (points.cols() == 3) {
for (size_t i = 0; i < points.rows(); i++) {
pc->point(i) << points.row(i).transpose(), 1.0;
.def(
py::init([](const Eigen::MatrixXd& points) {
if (points.cols() != 3 && points.cols() != 4) {
std::cerr << "points must be Nx3 or Nx4" << std::endl;
return std::make_shared<PointCloud>();
}
} else {
for (size_t i = 0; i < points.rows(); i++) {
pc->point(i) << points.row(i).transpose();
}
}
return pc;
})) //
auto pc = std::make_shared<PointCloud>();
pc->resize(points.rows());
if (points.cols() == 3) {
for (size_t i = 0; i < points.rows(); i++) {
pc->point(i) << points.row(i).transpose(), 1.0;
}
} else {
for (size_t i = 0; i < points.rows(); i++) {
pc->point(i) << points.row(i).transpose();
}
}
return pc;
}),
py::arg("points"),
R"""(
PointCloud(points: numpy.ndarray)
Construct a PointCloud from numpy.
Parameters
----------
points : numpy.ndarray, shape (n, 3) or (n, 4)
The input point cloud.
)""")
.def("__repr__", [](const PointCloud& points) { return "small_gicp.PointCloud (" + std::to_string(points.size()) + " points)"; })
.def("__len__", [](const PointCloud& points) { return points.size(); })
.def("empty", &PointCloud::empty, "Check if the point cloud is empty.")
.def("size", &PointCloud::size, "Get the number of points.")
.def(
"empty",
&PointCloud::empty,
R"pbdoc(
Check if the point cloud is empty
Returns
-------
empty : bool
True if the point cloud is empty.
)pbdoc")
.def(
"size",
&PointCloud::size,
R"pbdoc(
Get the number of points.
Returns
-------
num_points : int
Number of points.
)pbdoc")
.def(
"points",
[](const PointCloud& points) -> Eigen::MatrixXd { return Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(points.points[0].data(), points.size(), 4); },
"Get the points as a Nx4 matrix.")
R"pbdoc(
Get the points as a Nx4 matrix.
Returns
-------
points : numpy.ndarray
Points.
)pbdoc")
.def(
"normals",
[](const PointCloud& points) -> Eigen::MatrixXd { return Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(points.normals[0].data(), points.size(), 4); },
"Get the normals as a Nx4 matrix.")
R"pbdoc(
Get the normals as a Nx4 matrix.
Returns
-------
normals : numpy.ndarray
Normals.
)pbdoc")
.def(
"covs",
[](const PointCloud& points) { return points.covs; },
"Get the covariance matrices.")
R"pbdoc(
Get the covariance matrices as a list of 4x4 matrices.
Returns
-------
covs : list of numpy.ndarray
Covariance matrices.
)pbdoc")
.def(
"point",
[](const PointCloud& points, size_t i) -> Eigen::Vector4d { return points.point(i); },
py::arg("i"),
"Get the i-th point.")
R"pbdoc(
Get the i-th point.
Parameters
----------
i : int
Index of the point.
Returns
-------
point : numpy.ndarray, shape (4,)
Point.
)pbdoc")
.def(
"normal",
[](const PointCloud& points, size_t i) -> Eigen::Vector4d { return points.normal(i); },
py::arg("i"),
"Get the i-th normal.")
.def("cov", [](const PointCloud& points, size_t i) -> Eigen::Matrix4d { return points.cov(i); }, py::arg("i"), "Get the i-th covariance matrix.");
R"pbdoc(
Get the i-th normal.
Parameters
----------
i : int
Index of the point.
Returns
-------
normal : numpy.ndarray, shape (4,)
Normal.
)pbdoc")
.def(
"cov",
[](const PointCloud& points, size_t i) -> Eigen::Matrix4d { return points.cov(i); },
py::arg("i"),
R"pbdoc(
Get the i-th covariance matrix.
Parameters
----------
i : int
Index of the point.
Returns
-------
cov : numpy.ndarray, shape (4, 4)
Covariance matrix.
)pbdoc");
}

View File

@ -33,11 +33,11 @@ void define_result(py::module& m) {
.def_property_readonly(
"T_target_source",
[](const RegistrationResult& result) -> Eigen::Matrix4d { return result.T_target_source.matrix(); },
"Final transformation matrix")
.def_readonly("converged", &RegistrationResult::converged, "Convergence flag")
.def_readonly("iterations", &RegistrationResult::iterations, "Number of iterations")
.def_readonly("num_inliers", &RegistrationResult::num_inliers, "Number of inliers")
.def_readonly("H", &RegistrationResult::H, "Final Hessian matrix")
.def_readonly("b", &RegistrationResult::b, "Final information vector")
.def_readonly("error", &RegistrationResult::error, "Final error");
"NDArray[np.float64] : Final transformation matrix (4x4). This transformation brings a point in the source cloud frame to the target cloud frame.")
.def_readonly("converged", &RegistrationResult::converged, "bool : Convergence flag")
.def_readonly("iterations", &RegistrationResult::iterations, "int : Number of iterations")
.def_readonly("num_inliers", &RegistrationResult::num_inliers, "int : Number of inliers")
.def_readonly("H", &RegistrationResult::H, "NDArray[np.float64] : Final Hessian matrix (6x6)")
.def_readonly("b", &RegistrationResult::b, "NDArray[np.float64] : Final information vector (6,)")
.def_readonly("error", &RegistrationResult::error, "float : Final error");
}

View File

@ -18,7 +18,18 @@ using namespace small_gicp;
template <typename VoxelMap, bool has_normals, bool has_covs>
auto define_class(py::module& m, const std::string& name) {
py::class_<VoxelMap> vox(m, name.c_str());
vox.def(py::init<double>())
vox
.def(
py::init<double>(),
py::arg("leaf_size"),
R"pbdoc(
Construct a VoxelMap.
Parameters
----------
leaf_size : float
Voxel size.
)pbdoc")
.def(
"__repr__",
[=](const VoxelMap& voxelmap) {
@ -27,13 +38,32 @@ auto define_class(py::module& m, const std::string& name) {
return sst.str();
})
.def("__len__", [](const VoxelMap& voxelmap) { return voxelmap.size(); })
.def("size", &VoxelMap::size, "Get the number of voxels.")
.def(
"size",
&VoxelMap::size,
R"pbdoc(
Get the number of voxels.
Returns
-------
num_voxels : int
Number of voxels.
)pbdoc")
.def(
"insert",
[](VoxelMap& voxelmap, const PointCloud& points, const Eigen::Matrix4d& T) { voxelmap.insert(points, Eigen::Isometry3d(T)); },
py::arg("points"),
py::arg("T") = Eigen::Matrix4d::Identity(),
"Insert a point cloud.")
R"pbdoc(
Insert a point cloud into the voxel map.
Parameters
----------
points : PointCloud
Input source point cloud.
T : numpy.ndarray, optional
Transformation matrix to be applied to the input point cloud (i.e., T_voxelmap_source). (default: identity)
)pbdoc")
.def(
"set_lru",
[](VoxelMap& voxelmap, size_t horizon, size_t clear_cycle) {
@ -42,14 +72,30 @@ auto define_class(py::module& m, const std::string& name) {
},
py::arg("horizon") = 100,
py::arg("clear_cycle") = 10,
"Set the LRU cache parameters.")
R"pbdoc(
Set the LRU cache parameters.
Parameters
----------
horizon : int, optional
LRU horizon size. Voxels that have not been accessed for lru_horizon steps are deleted. (default: 100)
clear_cycle : int, optional
LRU clear cycle. Voxel deletion is performed every lru_clear_cycle steps. (default: 10)
)pbdoc")
.def(
"voxel_points",
[](const VoxelMap& voxelmap) -> Eigen::MatrixXd {
auto points = traits::voxel_points(voxelmap);
return Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(points[0].data(), points.size(), 4);
},
"Get the voxel points.");
R"pbdoc(
Get the voxel points.
Returns
-------
voxel_points : numpy.ndarray
Voxel points. (Nx4)
)pbdoc");
if constexpr (has_normals) {
vox.def(
@ -58,7 +104,14 @@ auto define_class(py::module& m, const std::string& name) {
auto normals = traits::voxel_normals(voxelmap);
return Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(normals[0].data(), normals.size(), 4);
},
"Get the voxel normals.");
R"pbdoc(
Get the voxel normals.
Returns
-------
voxel_normals : numpy.ndarray
Voxel normals. (Nx4)
)pbdoc");
}
if constexpr (has_covs) {
@ -68,7 +121,14 @@ auto define_class(py::module& m, const std::string& name) {
auto covs = traits::voxel_covs(voxelmap);
return Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(covs[0].data(), covs.size(), 16);
},
"Get the voxel covariance matrices.");
R"pbdoc(
Get the voxel normals.
Returns
-------
voxel_covs : list of numpy.ndarray
Voxel covariance matrices. (Nx4x4)
)pbdoc");
}
};