diff --git a/CMakeLists.txt b/CMakeLists.txt index 904d731..08b93b3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,17 +1,15 @@ cmake_minimum_required(VERSION 3.10) project(${SKBUILD_PROJECT_NAME} VERSION ${SKBUILD_PROJECT_VERSION}) -if(NOT DEFINED CMAKE_CUDA_ARCHITECTURES) - set(CMAKE_CUDA_ARCHITECTURES "native") +find_package(Ceres REQUIRED) +if(NOT TARGET Ceres::ceres) + # Older Ceres versions don't come with an imported interface target. + add_library(Ceres::ceres INTERFACE IMPORTED) + target_include_directories( + Ceres::ceres INTERFACE ${CERES_INCLUDE_DIRS}) + target_link_libraries( + Ceres::ceres INTERFACE ${CERES_LIBRARIES}) endif() -find_package(COLMAP REQUIRED) -if(${COLMAP_VERSION} VERSION_LESS "3.9.0") - message( SEND_ERROR "COLMAP version >= 3.9.0 required, found ${COLMAP_VERSION}." ) -endif() -if(${CERES_VERSION} VERSION_LESS "2.1.0") - message( SEND_ERROR "Ceres version >= 2.1 required, found ${CERES_VERSION}." ) -endif() - find_package(Python REQUIRED COMPONENTS Interpreter Development.Module) @@ -19,6 +17,6 @@ find_package(pybind11 2.11.1 REQUIRED) pybind11_add_module(pyceres _pyceres/bindings.cc) target_include_directories(pyceres PRIVATE ${PROJECT_SOURCE_DIR}) -target_link_libraries(pyceres PRIVATE colmap::colmap glog::glog Ceres::ceres) +target_link_libraries(pyceres PRIVATE glog::glog Ceres::ceres) target_compile_definitions(pyceres PRIVATE VERSION_INFO="${PROJECT_VERSION}") install(TARGETS pyceres LIBRARY DESTINATION .) diff --git a/Dockerfile b/Dockerfile index d57da3d..5f56853 100644 --- a/Dockerfile +++ b/Dockerfile @@ -2,9 +2,6 @@ ARG UBUNTU_VERSION=22.04 ARG NVIDIA_CUDA_VERSION=12.3.1 FROM nvidia/cuda:${NVIDIA_CUDA_VERSION}-devel-ubuntu${UBUNTU_VERSION} as builder -ARG COLMAP_VERSION=3.9.1 -ARG CUDA_ARCHITECTURES=70 -ENV CUDA_ARCHITECTURES=${CUDA_ARCHITECTURES} ENV QT_XCB_GL_INTEGRATION=xcb_egl # Prevent stop building ubuntu at time zone selection. @@ -17,21 +14,12 @@ RUN apt-get update && \ cmake \ ninja-build \ build-essential \ - libboost-program-options-dev \ - libboost-filesystem-dev \ - libboost-graph-dev \ - libboost-system-dev \ libeigen3-dev \ - libflann-dev \ - libfreeimage-dev \ - libmetis-dev \ libgoogle-glog-dev \ + libgflags-dev \ libgtest-dev \ - libsqlite3-dev \ - libglew-dev \ - qtbase5-dev \ - libqt5opengl5-dev \ - libcgal-dev \ + libatlas-base-dev \ + libsuitesparse-dev \ python-is-python3 \ python3-minimal \ python3-pip \ @@ -47,16 +35,7 @@ RUN apt-get install -y --no-install-recommends --no-install-suggests wget && \ cmake ../ceres-solver-2.1.0 -GNinja && \ ninja install -# Install Colmap. -RUN wget "https://github.com/colmap/colmap/archive/refs/tags/${COLMAP_VERSION}.tar.gz" -O colmap-${COLMAP_VERSION}.tar.gz && \ - tar zxvf colmap-${COLMAP_VERSION}.tar.gz && \ - mkdir colmap-build && \ - cd colmap-build && \ - cmake ../colmap-${COLMAP_VERSION} -GNinja -DCMAKE_CUDA_ARCHITECTURES=${CUDA_ARCHITECTURES} && \ - ninja install - - # Build pyceres. COPY . /pyceres WORKDIR /pyceres -RUN pip install . -vv --config-settings=cmake.define.CMAKE_CUDA_ARCHITECTURES=${CUDA_ARCHITECTURES} +RUN pip install . -vv diff --git a/README.md b/README.md index dfaa800..d004264 100644 --- a/README.md +++ b/README.md @@ -4,9 +4,7 @@ This repository provides minimal Python bindings for the [Ceres Solver](http://c ## Installation -1. Install [COLMAP 3.9.1](https://colmap.github.io/) - -2. Clone the repository and build the package: +Clone the repository and build the package: ```sh git clone https://github.com/cvg/pyceres.git @@ -14,36 +12,22 @@ cd pyceres python -m pip install . ``` -### Docker image - Alternatively, you can build the Docker image: ```sh -export COLMAP_VERSION=3.9.1 -export CUDA_ARCHITECTURES=70 -docker build -t pyceres \ - --build-arg COLMAP_VERSION=${COLMAP_VERSION} \ - --build-arg CUDA_ARCHITECTURES=${CUDA_ARCHITECTURES} \ - -f Dockerfile . +docker build -t pyceres -f Dockerfile . ``` ## Factor graph optimization -For now we support the following cost functions, defined in `_pyceres/factors/`: -- camera reprojection error (with fixed or variable pose) -- rig reprojection error (with fixed or variable rig extrinsics) -- relative pose prior -- absolute pose prior - -All factors support basic observation covariances. Reprojection error costs rely on camera models defined in COLMAP. Absolute poses are represented as quaternions and are expressed in the sensor frame, so are pose residuals, which use the right-hand convention as in the [GTSAM library](https://github.com/borglab/gtsam). - -## Examples -See the Jupyter notebooks in `examples/`. +Factors may be defined in Python (see [`examples/test_python_cost.py`](./examples/test_python_cost.py)) or in C++ with associated Python bindings. +[PyCOLMAP](https://github.com/colmap/colmap/tree/main/pycolmap) provides the following cost functions in `pycolmap.cost_functions`: +- reprojection error for different camera models, with fixed or variable pose and 3D points +- reprojection error for multi-camera rigs, with fixed or variable rig extrinsics +- error of absolute and relative poses +- Sampson error for epipolar geometry -## TODO -- [ ] Define a clean interface for covariances, like in GTSAM -- [ ] Add bindings for Ceres covariance estimation -- [ ] Proper benchmark against GTSAM +See [`examples/`](./examples/) to use these factors. ## Credits Pyceres was inspired by the work of Nikolaus Mitchell for [ceres_python_bindings](https://github.com/Edwinem/ceres_python_bindings) and is maintained by [Philipp Lindenberger](https://github.com/Phil26AT) and [Paul-Edouard Sarlin](https://psarlin.com/). diff --git a/_pyceres/factors/bindings.h b/_pyceres/factors/bindings.h index 3f2809f..31e25b7 100644 --- a/_pyceres/factors/bindings.h +++ b/_pyceres/factors/bindings.h @@ -1,85 +1,24 @@ #pragma once -#include "_pyceres/factors/bundle.h" -#include "_pyceres/factors/common.h" -#include "_pyceres/factors/pose_graph.h" #include "_pyceres/helpers.h" +#include +#include #include #include -#include namespace py = pybind11; -using namespace colmap; void bind_factors(py::module& m) { - m.def("ReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("point2D")); - m.def("ReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("point2D"), - py::arg("stddev")); - m.def("ReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("cam_from_world"), - py::arg("point2D")); - m.def("ReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("cam_from_world"), - py::arg("point2D"), - py::arg("stddev")); - - m.def("RigReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("point2D")); - m.def("RigReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("point2D"), - py::arg("stddev")); - m.def("RigReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("cam_from_rig"), - py::arg("point2D")); - m.def("RigReprojErrorCost", - &CreateCostFunction, - py::arg("camera_model_id"), - py::arg("cam_from_rig"), - py::arg("point2D"), - py::arg("stddev")); - - m.def("PoseGraphRelativeCost", - &PoseGraphRelativeCost::Create, - py::arg("j_from_i"), - py::arg("covariance")); - m.def("PoseGraphAbsoluteCost", - &PoseGraphAbsoluteCost::Create, - py::arg("cam_from_world"), - py::arg("covariance")); - - m.def("NormalPrior", - &CreateNormalPrior, - py::arg("mean"), - py::arg("covariance")); + m.def( + "NormalPrior", + [](const Eigen::VectorXd& mean, + const Eigen::Matrix& covariance) { + THROW_CHECK_EQ(covariance.cols(), mean.size()); + THROW_CHECK_EQ(covariance.cols(), covariance.rows()); + return new ceres::NormalPrior(covariance.inverse().llt().matrixL(), + mean); + }, + py::arg("mean"), + py::arg("covariance")); } diff --git a/_pyceres/factors/bundle.h b/_pyceres/factors/bundle.h deleted file mode 100644 index 0cee120..0000000 --- a/_pyceres/factors/bundle.h +++ /dev/null @@ -1,128 +0,0 @@ -#pragma once - -#include "_pyceres/log_exceptions.h" - -#include -#include -#include -#include -#include - -using namespace colmap; - -class LinearCostFunction : public ceres::CostFunction { - public: - LinearCostFunction(const double s) : s_(s) { - set_num_residuals(1); - mutable_parameter_block_sizes()->push_back(1); - } - - bool Evaluate(double const* const* parameters, - double* residuals, - double** jacobians) const final { - *residuals = **parameters * s_; - if (jacobians && *jacobians) { - **jacobians = s_; - } - return true; - } - - private: - const double s_; -}; - -template -class CostFunctionIsotropicNoise { - public: - static ceres::CostFunction* Create(Args&&... args, const double stddev) { - THROW_CHECK_GE(stddev, 0.0); - ceres::CostFunction* cost_function = - CostFunction::Create(std::forward(args)...); - std::vector conditioners( - cost_function->num_residuals(), new LinearCostFunction(1.0 / stddev)); - return new ceres::ConditionedCostFunction( - cost_function, conditioners, ceres::TAKE_OWNERSHIP); - } -}; - -template -class RigReprojErrorConstantRigCostFunction - : public ReprojErrorCostFunction { - using Parent = ReprojErrorCostFunction; - - public: - explicit RigReprojErrorConstantRigCostFunction(const Rigid3d& cam_from_rig, - const Eigen::Vector2d& point2D) - : Parent(point2D), cam_from_rig_(cam_from_rig) {} - - static ceres::CostFunction* Create(const Rigid3d& cam_from_rig, - const Eigen::Vector2d& point2D) { - return (new ceres::AutoDiffCostFunction< - RigReprojErrorConstantRigCostFunction, - 2, - 4, - 3, - 3, - CameraModel::num_params>( - new RigReprojErrorConstantRigCostFunction(cam_from_rig, point2D))); - } - - template - bool operator()(const T* const rig_from_world_rotation, - const T* const rig_from_world_translation, - const T* const point3D, - const T* const camera_params, - T* residuals) const { - const Eigen::Quaternion cam_from_world_rotation = - cam_from_rig_.rotation.cast() * - EigenQuaternionMap(rig_from_world_rotation); - const Eigen::Matrix cam_from_world_translation = - cam_from_rig_.rotation.cast() * - EigenVector3Map(rig_from_world_translation) + - cam_from_rig_.translation.cast(); - return Parent::operator()(cam_from_world_rotation.coeffs().data(), - cam_from_world_translation.data(), - point3D, - camera_params, - residuals); - } - - private: - const Rigid3d& cam_from_rig_; -}; - -template -using ReprojErrorCostFunctionWithNoise = - CostFunctionIsotropicNoise, - const Eigen::Vector2d&>; - -template -using ReprojErrorConstantPoseCostFunctionWithNoise = - CostFunctionIsotropicNoise, - const Rigid3d&, - const Eigen::Vector2d&>; - -template -using RigReprojErrorCostFunctionWithNoise = - CostFunctionIsotropicNoise, - const Eigen::Vector2d&>; - -template -using RigReprojErrorConstantRigCostFunctionWithNoise = - CostFunctionIsotropicNoise< - RigReprojErrorConstantRigCostFunction, - const Rigid3d&, - const Eigen::Vector2d&>; - -template