Berkeley SfM
Public Member Functions | Private Member Functions | List of all members
bsfm::BundleAdjuster Class Reference

#include <bundle_adjuster.h>

Public Member Functions

 BundleAdjuster ()
 
 ~BundleAdjuster ()
 
bool Solve (const BundleAdjustmentOptions &options, const std::vector< ViewIndex > &view_indices) const
 

Private Member Functions

bool ConvertOptionsToCeresOptions (const BundleAdjustmentOptions &options, ceres::Solver::Options *ceres_options) const
 

Detailed Description

Definition at line 72 of file bundle_adjuster.h.

Constructor & Destructor Documentation

bsfm::BundleAdjuster::BundleAdjuster ( )
inline

Definition at line 74 of file bundle_adjuster.h.

74 { }
bsfm::BundleAdjuster::~BundleAdjuster ( )
inline

Definition at line 75 of file bundle_adjuster.h.

75 { }

Member Function Documentation

bool bsfm::BundleAdjuster::ConvertOptionsToCeresOptions ( const BundleAdjustmentOptions options,
ceres::Solver::Options *  ceres_options 
) const
private

Definition at line 132 of file bundle_adjuster.cpp.

134  {
135  CHECK_NOTNULL(ceres_options);
136 
137  // Trust region strategy must be LM.
138  ceres_options->trust_region_strategy_type = ceres::LEVENBERG_MARQUARDT;
139 
140  // Set linear solver type.
141  if (options.solver_type.compare("DENSE_QR")==0) {
142  ceres_options->linear_solver_type = ceres::DENSE_QR;
143  } else if (options.solver_type.compare("DENSE_NORMAL_CHOLESKY")==0) {
144  ceres_options->linear_solver_type = ceres::DENSE_NORMAL_CHOLESKY;
145  } else if (options.solver_type.compare("SPARSE_NORMAL_CHOLESKY")==0) {
146  ceres_options->linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
147  } else if (options.solver_type.compare("CGNR")==0) {
148  ceres_options->linear_solver_type = ceres::CGNR;
149  } else if (options.solver_type.compare("DENSE_SCHUR")==0) {
150  ceres_options->linear_solver_type = ceres::DENSE_SCHUR;
151  } else if (options.solver_type.compare("SPARSE_SCHUR")==0) {
152  ceres_options->linear_solver_type = ceres::SPARSE_SCHUR;
153  } else if (options.solver_type.compare("ITERATIVE_SCHUR")==0) {
154  ceres_options->linear_solver_type = ceres::ITERATIVE_SCHUR;
155  } else {
156  ceres_options->linear_solver_type = ceres::SPARSE_SCHUR;
157  }
158 
159  // Set print progress.
160  if (options.print_progress) {
161  ceres_options->logging_type = ceres::PER_MINIMIZER_ITERATION;
162  ceres_options->minimizer_progress_to_stdout = true;
163  } else {
164  ceres_options->logging_type = ceres::SILENT;
165  ceres_options->minimizer_progress_to_stdout = false;
166  }
167 
168  // Set gradient and function tolerance.
169  ceres_options->gradient_tolerance = options.gradient_tolerance;
170  ceres_options->function_tolerance = options.function_tolerance;
171 
172  // Make sure the options we set are valid.
173  std::string error_message;
174  bool valid_options = ceres_options->IsValid(&error_message);
175  if (!valid_options) {
176  LOG(WARNING) << "Ceres options error: " << error_message;
177  }
178  return valid_options;
179 }
bool bsfm::BundleAdjuster::Solve ( const BundleAdjustmentOptions options,
const std::vector< ViewIndex > &  view_indices 
) const

Definition at line 49 of file bundle_adjuster.cpp.

50  {
51  // Create a ceres optimization problem.
52  ceres::Problem problem;
53 
54  // Create storage containers for optimization variables. We only do this
55  // because camera extrinsics by default are represented as a 4x4 homogeneous
56  // matrix, and we would prefer to optimize 6 camera variables (rotation and
57  // translation) instead of 16.
58  std::vector<Vector3d> rotations(view_indices.size());
59  std::vector<Vector3d> translations(view_indices.size());
60 
61  for (size_t ii = 0; ii < view_indices.size(); ++ii) {
62  View::Ptr view = View::GetView(view_indices[ii]);
63  if (view == nullptr) {
64  LOG(WARNING) << "View is null. Cannot perform bundle adjustment.";
65  return false;
66  }
67 
68  // Get camera extrinsics matrix for optimization.
69  rotations[ii] = view->Camera().AxisAngleRotation();
70  translations[ii] = view->Camera().Translation();
71 
72  // Get static camera intrinsics for evaluating cost function.
73  Matrix3d K = view->Camera().K();
74 
75  // Make a new residual block on the problem for every 3D point that this
76  // view sees.
77  const std::vector<Observation::Ptr> observations = view->Observations();
78  for (size_t jj = 0; jj < observations.size(); ++jj) {
79  CHECK_NOTNULL(observations[jj].get());
80  if (!observations[jj]->IsIncorporated())
81  continue;
82 
83  Landmark::Ptr landmark = observations[jj]->GetLandmark();
84  if (landmark == nullptr) {
85  LOG(WARNING) << "Landmark is null. Cannot perform bundle adjustment.";
86  return false;
87  }
88 
89  // Make sure the landmark has been seen by at least two of the views we
90  // are doing bundle adjustment over.
91  if (!landmark->SeenByAtLeastTwoViews(view_indices))
92  continue;
93 
94  // Add a residual block to the cost function.
95  problem.AddResidualBlock(
96  BundleAdjustmentError::Create(observations[jj]->Feature(), K),
97  NULL, /* squared loss */
98  rotations[ii].data(),
99  translations[ii].data(),
100  landmark->PositionData());
101  }
102  }
103 
104  // Solve the bundle adjustment problem.
105  ceres::Solver::Options ceres_options;
106  if (!ConvertOptionsToCeresOptions(options, &ceres_options)) {
107  LOG(WARNING) << "Bundle adjustment options are not valid.";
108  }
109 
110  ceres::Solver::Summary summary;
111  ceres::Solve(ceres_options, &problem, &summary);
112 
113  // Print a summary of the optimization.
114  if (options.print_summary) {
115  std::cout << summary.FullReport() << std::endl;
116  }
117 
118  // Assign optimized camera parameters back into views.
119  for (size_t ii = 0; ii < view_indices.size(); ++ii) {
120  Pose pose;
121  pose.FromAxisAngle(rotations[ii]);
122 
123  // We already know this view is not null.
124  View::Ptr view = View::GetView(view_indices[ii]);
125  view->MutableCamera().MutableExtrinsics().SetWorldToCamera(pose);
126  view->MutableCamera().MutableExtrinsics().SetTranslation(translations[ii]);
127  }
128 
129  return summary.IsSolutionUsable();
130 }
static ceres::CostFunction * Create(const Feature &x, const Matrix3d &K)
static View::Ptr GetView(ViewIndex view_index)
Definition: view.cpp:60
std::shared_ptr< Landmark > Ptr
Definition: landmark.h:66
std::shared_ptr< View > Ptr
Definition: view.h:66
bool ConvertOptionsToCeresOptions(const BundleAdjustmentOptions &options, ceres::Solver::Options *ceres_options) const

The documentation for this class was generated from the following files: