52 ceres::Problem problem;
58 std::vector<Vector3d> rotations(view_indices.size());
59 std::vector<Vector3d> translations(view_indices.size());
61 for (
size_t ii = 0; ii < view_indices.size(); ++ii) {
63 if (view ==
nullptr) {
64 LOG(WARNING) <<
"View is null. Cannot perform bundle adjustment.";
69 rotations[ii] = view->Camera().AxisAngleRotation();
70 translations[ii] = view->Camera().Translation();
73 Matrix3d K = view->Camera().K();
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())
84 if (landmark ==
nullptr) {
85 LOG(WARNING) <<
"Landmark is null. Cannot perform bundle adjustment.";
91 if (!landmark->SeenByAtLeastTwoViews(view_indices))
95 problem.AddResidualBlock(
99 translations[ii].data(),
100 landmark->PositionData());
105 ceres::Solver::Options ceres_options;
107 LOG(WARNING) <<
"Bundle adjustment options are not valid.";
110 ceres::Solver::Summary summary;
111 ceres::Solve(ceres_options, &problem, &summary);
114 if (options.print_summary) {
115 std::cout << summary.FullReport() << std::endl;
119 for (
size_t ii = 0; ii < view_indices.size(); ++ii) {
121 pose.FromAxisAngle(rotations[ii]);
125 view->MutableCamera().MutableExtrinsics().SetWorldToCamera(pose);
126 view->MutableCamera().MutableExtrinsics().SetTranslation(translations[ii]);
129 return summary.IsSolutionUsable();
static ceres::CostFunction * Create(const Feature &x, const Matrix3d &K)
static View::Ptr GetView(ViewIndex view_index)
std::shared_ptr< Landmark > Ptr
std::shared_ptr< View > Ptr
bool ConvertOptionsToCeresOptions(const BundleAdjustmentOptions &options, ceres::Solver::Options *ceres_options) const