void Run()

in opensfm/src/bundle/reconstruction_alignment.h [479:570]


  void Run() {
    ceres::Problem problem;

    // Init paramater blocks.
    for (auto &i : shots_) {
      if (i.second.constant) {
        problem.AddParameterBlock(i.second.parameters, RA_SHOT_NUM_PARAMS);
        problem.SetParameterBlockConstant(i.second.parameters);
      }
    }

    for (auto &i : reconstructions_) {
      problem.AddParameterBlock(i.second.parameters,
                                RA_RECONSTRUCTION_NUM_PARAMS);
      if (i.second.constant) {
        problem.SetParameterBlockConstant(i.second.parameters);
      } else {
        problem.SetParameterLowerBound(i.second.parameters,
                                       RA_RECONSTRUCTION_SCALE, 0.1);
        problem.SetParameterUpperBound(i.second.parameters,
                                       RA_RECONSTRUCTION_SCALE,
                                       std::numeric_limits<double>::max());
      }
    }

    // Add relative motion errors
    ceres::LossFunction *loss = new ceres::CauchyLoss(1.0);
    for (auto &rp : relative_motions_) {
      ceres::CostFunction *cost_function =
          new ceres::AutoDiffCostFunction<RARelativeMotionError, 6, 7, 6>(
              new RARelativeMotionError(rp.parameters, rp.scale_matrix));

      problem.AddResidualBlock(
          cost_function, loss,
          reconstructions_[rp.reconstruction_id].parameters,
          shots_[rp.shot_id].parameters);
    }

    // Add absolute position errors
    for (auto &a : absolute_positions_) {
      ceres::CostFunction *cost_function =
          new ceres::AutoDiffCostFunction<RAAbsolutePositionError, 3, 6>(
              new RAAbsolutePositionError(a.position, a.std_deviation));

      problem.AddResidualBlock(cost_function, NULL, a.shot->parameters);
    }

    // Add relative-absolute position errors
    ceres::LossFunction *l1_loss = new ceres::SoftLOneLoss(1.0);
    for (auto &a : relative_absolute_positions_) {
      ceres::CostFunction *cost_function =
          new ceres::AutoDiffCostFunction<RARelativeAbsolutePositionError, 3,
                                          7>(
              new RARelativeAbsolutePositionError(
                  a.position, a.shot->parameters, a.std_deviation));

      problem.AddResidualBlock(cost_function, l1_loss,
                               a.reconstruction->parameters);
    }

    // Add common cameras constraints
    for (auto &a : common_cameras_) {
      ceres::CostFunction *cost_function =
          new ceres::AutoDiffCostFunction<RACommonCameraError, 6, 7, 7>(
              new RACommonCameraError(
                  a.shot_a->parameters, a.shot_b->parameters,
                  a.std_deviation_center, a.std_deviation_rotation));

      problem.AddResidualBlock(cost_function, loss,
                               a.reconstruction_a->parameters,
                               a.reconstruction_b->parameters);
    }

    // Add common point errors
    for (auto &a : common_points_) {
      ceres::CostFunction *cost_function =
          new ceres::AutoDiffCostFunction<RACommonPointError, 3, 7, 7>(
              new RACommonPointError(a.point_a, a.point_b, a.std_deviation));

      problem.AddResidualBlock(cost_function, l1_loss,
                               a.reconstruction_a->parameters,
                               a.reconstruction_b->parameters);
    }

    // Solve
    ceres::Solver::Options options;
    options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
    options.num_threads = 8;
    options.max_num_iterations = 500;

    ceres::Solve(options, &problem, &last_run_summary_);
  }