cvg / pixel-perfect-sfm

Pixel-Perfect Structure-from-Motion with Featuremetric Refinement (ICCV 2021, Best Student Paper Award)
Apache License 2.0
1.33k stars 135 forks source link

undefined symbol error on using with COLMAP 3.9.1 #137

Open shubham-monarch opened 7 months ago

shubham-monarch commented 7 months ago

After updating to COLMAP 3.9.1, I wasn't able to install PixSFM using pip install -e . --verbose.

To make it work, I made a lot of changes to the PixSFM repo (will make a pull request later) and was able to install it successfully.

However, when I am trying to import PixSFM in my notebook as follows =>

%load_ext autoreload
%autoreload 2
import tqdm, tqdm.notebook
tqdm.tqdm = tqdm.notebook.tqdm  # notebook-friendly progress bars
from pathlib import Path
import os
import time
import sys
from hloc import extract_features, match_features, reconstruction, pairs_from_exhaustive, visualization
from hloc.visualization import plot_images, read_image
from hloc.utils.viz_3d import init_figure, plot_points, plot_reconstruction, plot_camera_colmap

from pixsfm.util.visualize import init_image, plot_points2D
from pixsfm.refine_hloc import PixSfM
from pixsfm import ostream_redirect
from PIL import Image, ImageDraw
import pycolmap
import visualize_model
# redirect the C++ outputs to notebook cells
cpp_out = ostream_redirect(stderr=True, stdout=True)
cpp_out.__enter__() 

I am getting the following error =>

ImportError                               Traceback (most recent call last)
Cell In[1], line 13
     10 from hloc.visualization import plot_images, read_image
     11 from hloc.utils.viz_3d import init_figure, plot_points, plot_reconstruction, plot_camera_colmap
---> 13 from pixsfm.util.visualize import init_image, plot_points2D
     14 from pixsfm.refine_hloc import PixSfM
     15 from pixsfm import ostream_redirect

File ~/pixel-perfect-sfm/pixsfm/__init__.py:17
     14 logger.propagate = False
     16 import pyceres  # noqa F403
---> 17 from ._pixsfm import *  # noqa F403
     19 from . import (  # noqa F403
     20     base, features, bundle_adjustment, keypoint_adjustment,
     21     extract, localization, util, cpplog
     22 )
     24 cpplog.level = 1  # do not log DEBUG

ImportError: /home/skumar/pixel-perfect-sfm/pixsfm/_pixsfm.cpython-38-x86_64-linux-gnu.so: undefined symbol: _ZNK6colmap22BundleAdjustmentConfig16HasConstantPointEm

It looks like some sort of binding error to me. Let me also share the updated bundle_adjustment/bindings.cc , bundle_adjustment/src/bundle_adjustment_options.h and bundle_adjustment_options.cc with you =>

bindings.cc

#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include "_pixsfm/src/helpers.h"

#include "bundle_adjustment/src/bundle_adjustment_options.h"
#include "bundle_adjustment/src/bundle_optimizer.h"
#include "bundle_adjustment/src/costmap_bundle_optimizer.h"
#include "bundle_adjustment/src/feature_reference_bundle_optimizer.h"
#include "bundle_adjustment/src/geometric_bundle_optimizer.h"
#include "bundle_adjustment/src/patch_warp_bundle_optimizer.h"

#include "bundle_adjustment/src/costmap_extractor.h"
#include "bundle_adjustment/src/reference_extractor.h"

namespace pixsfm {

template <typename dtype, typename T>
void BindCostMapExtractor(py::class_<T>& class_) {
  class_.def("run", &CostMapExtractor::Run<dtype, dtype>,
             py::arg("problem_labels"), py::arg("feature_set").noconvert(),
             py::arg("reconstruction").noconvert(),
             py::arg("ref_extractor").noconvert(),
             py::call_guard<py::gil_scoped_release>(), py::keep_alive<1, 3>());
}

template <typename dtype, typename T>
void BindReferenceExtractor(py::class_<T>& class_) {
  class_.def("run", &ReferenceExtractor::Run<dtype>, py::arg("problem_labels"),
             py::arg("reconstruction").noconvert(),
             py::arg("feature_set").noconvert(),
             py::call_guard<py::gil_scoped_release>(), py::keep_alive<1, 3>());
}

template <typename dtype, typename T>
void BindBundleOptimizer(py::class_<T>& class_) {
  class_.def("run", &T::template Run<dtype>);
  class_.def("set_up", &T::template SetUp<dtype>);
}

template <typename T>
void BindBundleOptimizer(py::class_<T>& class_) {
  BindBundleOptimizer<half>(class_);
  BindBundleOptimizer<float>(class_);
  BindBundleOptimizer<double>(class_);
  class_.def("summary", &T::Summary);
  class_.def_property_readonly("problem", &T::Problem);
  class_.def("solve_problem", &T::SolveProblem);
  class_.def("reset", &T::Reset);
}

void bind_bundle_adjustment(py::module& m) {
  auto costmapconf =
      py::class_<CostMapConfig>(m, "CostMapConfig")
          .def(py::init<>())
          .def_readwrite("as_gradientfield", &CostMapConfig::as_gradientfield)
          .def_readwrite("upsampling_factor", &CostMapConfig::upsampling_factor)
          .def_readwrite("compute_cross_derivative",
                         &CostMapConfig::compute_cross_derivative)
          .def("get_effective_channels", &CostMapConfig::GetEffectiveChannels)
          .def_readwrite("apply_sqrt", &CostMapConfig::apply_sqrt)
          .def_readwrite("dense_cut_size", &CostMapConfig::dense_cut_size)
          .def_readwrite("num_threads", &CostMapConfig::num_threads)
          .def_readwrite("loss", &CostMapConfig::loss, py::keep_alive<1, 2>());
  make_dataclass(costmapconf);

  auto refconf =
      py::class_<ReferenceConfig>(m, "ReferenceConfig")
          .def(py::init<>())
          .def_readwrite("iters", &ReferenceConfig::iters)
          .def_readwrite("keep_observations",
                         &ReferenceConfig::keep_observations)
          .def_readwrite("num_threads", &ReferenceConfig::num_threads)
          .def_readwrite("compute_offsets3D",
                         &ReferenceConfig::compute_offsets3D)
          .def_readwrite("loss", &ReferenceConfig::loss,
                         py::keep_alive<1, 2>());
  make_dataclass(refconf);

  py::class_<BundleAdjustmentSetup>(m, "BundleAdjustmentSetup")
      .def(py::init<>())
      .def("add_image", &BundleAdjustmentSetup::AddImage)
      .def("add_images",
           [](BundleAdjustmentSetup& self,
              std::unordered_set<colmap::image_t> image_ids) {
             for (colmap::image_t image_id : image_ids) {
               self.AddImage(image_id);
             }
           })
      .def("set_constant_camera", &BundleAdjustmentSetup::SetConstantCamIntrinsics)
      .def("set_variable_camera", &BundleAdjustmentSetup::SetVariableCamIntrinsics)
      .def("is_constant_camera", &BundleAdjustmentSetup::HasConstantCamIntrinsics)
      .def("set_constant_pose", &BundleAdjustmentSetup::SetConstantPose)
      .def("set_variable_pose", &BundleAdjustmentSetup::SetVariableCamPose)
      .def("has_constant_pose", &BundleAdjustmentSetup::HasConstantCamPose)
      .def("set_constant_tvec", &BundleAdjustmentSetup::SetConstantTvec)
      .def("remove_constant_tvec", &BundleAdjustmentSetup::RemoveConstantCamPositions)
      .def("has_constant_tvec", &BundleAdjustmentSetup::HasConstantCamPositions)
      .def("add_variable_point", &BundleAdjustmentSetup::AddVariablePoint)
      .def("add_constant_point", &BundleAdjustmentSetup::AddConstantPoint)
      .def("has_point", &BundleAdjustmentSetup::HasPoint)
      .def("has_variable_point", &BundleAdjustmentSetup::HasVariablePoint)
      .def("has_constant_point", &BundleAdjustmentSetup::HasConstantPoint)
      //.def("remove_variable_point", &BundleAdjustmentSetup::RemoveVariablePoint)
      .def("remove_constant_point", &BundleAdjustmentSetup::RemoveConstantPoint)
      .def_property_readonly("image_ids", &BundleAdjustmentSetup::Images)
      .def_property_readonly("variable_point3D_ids",
                             &BundleAdjustmentSetup::VariablePoints)
      .def_property_readonly("constant_point3D_ids",
                             &BundleAdjustmentSetup::ConstantPoints);

  auto ba_options =
      py::class_<BundleOptimizerOptions>(m, "BundleOptimizerOptions")
          .def(py::init<>([]() {
            BundleOptimizerOptions options = BundleOptimizerOptions();
            options.register_pyinterrupt_callback = true;
            return options;
          }))
          .def_readwrite("refine_focal_length",
                         &BundleOptimizerOptions::refine_focal_length)
          .def_readwrite("refine_extra_params",
                         &BundleOptimizerOptions::refine_extra_params)
          .def_readwrite("refine_extrinsics",
                         &BundleOptimizerOptions::refine_extrinsics)
          .def_readwrite("refine_principal_point",
                         &BundleOptimizerOptions::refine_principal_point)
          .def_readwrite("solver", &BundleOptimizerOptions::solver_options)
          .def_readwrite("min_track_length",
                         &BundleOptimizerOptions::min_track_length)
          .def_readwrite("print_summary",
                         &BundleOptimizerOptions::print_summary)
          .def_readwrite("loss", &BundleOptimizerOptions::loss,
                         py::keep_alive<1, 2>());
  make_dataclass(ba_options);

  auto frba = py::class_<FeatureReferenceBundleOptimizer>(
                  m, "FeatureReferenceBundleOptimizer")
                  .def(py::init<BundleOptimizerOptions, BundleAdjustmentSetup,
                                InterpolationConfig>());
  BindBundleOptimizer(frba);

  auto cmba = py::class_<CostMapBundleOptimizer>(m, "CostMapBundleOptimizer")
                  .def(py::init<BundleOptimizerOptions, BundleAdjustmentSetup,
                                InterpolationConfig>());
  BindBundleOptimizer(cmba);

  auto pwba =
      py::class_<PatchWarpBundleOptimizer>(m, "PatchWarpBundleOptimizer")
          .def(py::init<PatchWarpBundleOptimizer::Options,
                        BundleAdjustmentSetup, InterpolationConfig>());
  BindBundleOptimizer(pwba);

  auto gba =
      py::class_<GeometricBundleOptimizer>(m, "GeometricBundleOptimizer")
          .def(py::init<BundleOptimizerOptions, BundleAdjustmentSetup>())
          .def("run", &GeometricBundleOptimizer::Run)
          .def("set_up", &GeometricBundleOptimizer::SetUp)
          .def("summary", &GeometricBundleOptimizer::Summary)
          .def_property_readonly("problem", &GeometricBundleOptimizer::Problem)
          .def("solve_problem", &GeometricBundleOptimizer::SolveProblem)
          .def("reset", &GeometricBundleOptimizer::Reset);

  auto pw_options =
      py::class_<PatchWarpBundleOptimizer::Options>(
          m, "PatchWarpBundleOptimizerOptions", ba_options)  // inherit
          .def(py::init<>())
          .def_readwrite("regularize_source",
                         &PatchWarpBundleOptimizer::Options::regularize_source);
  make_dataclass(pw_options);

  auto r = py::class_<ReferenceExtractor>(m, "ReferenceExtractor")
               .def(py::init<ReferenceConfig&, InterpolationConfig&>());

  BindReferenceExtractor<half>(r);
  BindReferenceExtractor<float>(r);
  BindReferenceExtractor<double>(r);

  auto c = py::class_<CostMapExtractor>(m, "CostMapExtractor")
               .def(py::init<CostMapConfig&, InterpolationConfig&>());

  BindCostMapExtractor<half>(c);
  BindCostMapExtractor<float>(c);
  BindCostMapExtractor<double>(c);
}

}  // namespace pixsfm

bundle_adjustment_options.h

#pragma once
#include "_pixsfm/src/helpers.h"
#include <pybind11/numpy.h>
#include <pybind11/pybind11.h>

namespace py = pybind11;

#include <highfive/H5DataSet.hpp>
#include <highfive/H5DataSpace.hpp>
#include <highfive/H5File.hpp>
#include <highfive/H5Group.hpp>

#include <ceres/ceres.h>
//#include <colmap/base/projection.h>
//#include <colmap/base/reconstruction.h>
#include <colmap/scene/reconstruction.h>
//#include <colmap/optim/bundle_adjustment.h>
#include <colmap/estimators/bundle_adjustment.h>
#include <colmap/util/types.h>

#include "features/src/featuremap.h"
#include "features/src/featurepatch.h"
#include "features/src/featureset.h"

#include "util/src/types.h"

namespace pixsfm {

// Configuration container to setup bundle adjustment problems.
class BundleAdjustmentSetup : public colmap::BundleAdjustmentConfig {
 public:
  BundleAdjustmentSetup() : colmap::BundleAdjustmentConfig() {}
  BundleAdjustmentSetup(const colmap::BundleAdjustmentConfig& config)
      : colmap::BundleAdjustmentConfig(config) {}

  // Overwrite methods which trigger glog
  void SetConstantPose(const colmap::image_t image_id);
  void SetConstantTvec(const colmap::image_t image_id,
                       const std::vector<int>& idxs);
  void AddVariablePoint(const colmap::point3D_t point3D_id);
  void AddConstantPoint(const colmap::point3D_t point3D_id);

  inline void SetAllConstant(colmap::Reconstruction* reconstruction);
};

struct BundleOptimizerOptions {
  // Ceres-Solver options.
  ceres::Solver::Options solver_options;

  BundleOptimizerOptions() {
    loss.reset(new ceres::CauchyLoss(0.25));
    solver_options.function_tolerance = 0.0;
    solver_options.gradient_tolerance = 0.0;
    solver_options.parameter_tolerance = 0.0;
    solver_options.minimizer_progress_to_stdout = true;
    solver_options.max_num_iterations = 100;
    solver_options.max_linear_solver_iterations = 200;
    solver_options.max_num_consecutive_invalid_steps = 10;
    solver_options.max_consecutive_nonmonotonic_steps = 10;
    solver_options.num_threads = -1;
#if CERES_VERSION_MAJOR < 2
    solver_options.num_linear_solver_threads = -1;
#endif  // CERES_VERSION_MAJOR
    // Since we use smart pointers to manage loss functions
    problem_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
  }

  // Whether to refine the focal length parameter group.
  bool refine_focal_length = true;

  // Whether to refine the principal point parameter group.
  bool refine_principal_point = false;

  // Whether to refine the extra parameter group.
  bool refine_extra_params = true;

  // Whether to refine the extrinsic parameter group.
  bool refine_extrinsics = true;

  // Whether to print a final summary.
  bool print_summary = true;

  // Minimum number of residuals to enable multi-threading. Note that
  // single-threaded is typically better for small bundle adjustment problems
  // due to the overhead of threading.
  int min_num_residuals_for_multi_threading = 50000;

  bool Check() const;

  std::shared_ptr<ceres::LossFunction> loss;

  int min_track_length =
      -1;  // Use this to control which points should be optimized

  // Python only options
  ceres::Problem::Options problem_options;

  // Whether the solver should be interruptable from python
  bool register_pyinterrupt_callback = false;
};

}  // namespace pixsfm

bundle_adjustment_options.cc

#include "bundle_adjustment/src/bundle_adjustment_options.h"

#include <colmap/util/misc.h>

namespace pixsfm {

void BundleAdjustmentSetup::SetConstantPose(const colmap::image_t image_id) {
  THROW_CHECK(HasImage(image_id));
  //THROW_CHECK(!HasConstantTvec(image_id));
  THROW_CHECK(!HasConstantCamPositions(image_id));
  //colmap::BundleAdjustmentConfig::SetConstantPose(image_id);
  colmap::BundleAdjustmentConfig::SetConstantCamPose(image_id);
}

void BundleAdjustmentSetup::SetConstantTvec(const colmap::image_t image_id,
                                            const std::vector<int>& idxs) {
  THROW_CHECK_GT(idxs.size(), 0);
  THROW_CHECK_LE(idxs.size(), 3);
  THROW_CHECK(HasImage(image_id));
  THROW_CHECK(!HasConstantCamPose(image_id));
  THROW_CHECK(!colmap::VectorContainsDuplicateValues(idxs));
  //colmap::BundleAdjustmentConfig::SetConstantTvec(image_id, idxs);
  colmap::BundleAdjustmentConfig::SetConstantCamPositions(image_id, idxs);
}
void BundleAdjustmentSetup::AddVariablePoint(
    const colmap::point3D_t point3D_id) {
  THROW_CHECK(!HasConstantPoint(point3D_id));
  colmap::BundleAdjustmentConfig::AddVariablePoint(point3D_id);
}
void BundleAdjustmentSetup::AddConstantPoint(
    const colmap::point3D_t point3D_id) {
  THROW_CHECK(!HasVariablePoint(point3D_id));
  colmap::BundleAdjustmentConfig::AddConstantPoint(point3D_id);
}
}  // namespace pixsfm
ichsan2895 commented 7 months ago

Pixsfm must be built with: ceres-solver 2.1.0. The newer one (2.2.0) is not working. pyceres v1.0 with CUDA that built by ceres-solver 2.1.0. pycolmap 0.4.0 with CUDA that built by ceres-solver 2.1.0. hloc 1.4 with CUDA that built by ceres-solver 2.1.0. instead of hloc 1.5 colmap 3.8 with CUDA that built by ceres-solver 2.1.0 instead of colmap 3.9.1 .

Maybe we must add it explicitly in readme for clearer instruction.

creiser commented 6 months ago

@ichsan2895 Thanks for this list. I had not figured out yet that you need ceres-solver 2.1.0 and hloc 1.4, which is not documented anywhere yet. Also: For COLMAP 3.8 you need CUDA 11.x which in turn requires a gcc <= 10 (higher versions won't work). Also use cmake 3.26.