Skip to content

Commit

Permalink
Document the two passes
Browse files Browse the repository at this point in the history
  • Loading branch information
oleg-alexandrov committed Aug 16, 2024
1 parent c3e310b commit b3827c5
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 4 deletions.
3 changes: 2 additions & 1 deletion NEWS.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ jitter_solve (:numref:`jitter_solve`):
* Add an example for the Kaguya Terrain Camera (:numref:`jitter_kaguya`).
* Can use GCP files.
* Can read a control network from an nvm file.

* Do two passes. This improves the results.

stereo_gui (:numref:`stereo_gui`):
* Changing the image threshold updates the display correctly.
* When creating GCP, ask before quitting without saving them. Save the IP as
Expand Down
5 changes: 5 additions & 0 deletions docs/tools/jitter_solve.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2121,6 +2121,11 @@ Command-line options for jitter_solve
ahead of the camera, in units of meters. Some of these
may be later filtered as outliers.

--num-passes <integer (default: 2)>
How many passes of jitter solving to do, with the given number of iterations
in each pass. Each pass uses the previously refined cameras, which improves
the accuracy of the DEM constraint and the final result.

--rig-config <string>
Assume that the cameras are acquired with a set of rigs with this
configuration file (:numref:`jitter_rig`). The intrinsics will be read, but
Expand Down
2 changes: 1 addition & 1 deletion src/asp/Camera/BundleAdjustResiduals.cc
Original file line number Diff line number Diff line change
Expand Up @@ -467,7 +467,7 @@ void saveTriOffsetsPerCamera(std::vector<std::string> const& image_files,

// Sanity check
if (ipt < 0 || ipt >= num_points)
vw_throw(LogicErr() << "Invalid point index " << ipt
vw::vw_throw(vw::LogicErr() << "Invalid point index " << ipt
<< " in saveTriOffsetsPerCamera().\n");

if (outliers.find(ipt) != outliers.end())
Expand Down
13 changes: 11 additions & 2 deletions src/asp/Tools/jitter_solve.cc
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,7 @@ void handle_arguments(int argc, char *argv[], Options& opt, rig::RigSet & rig) {
("num-passes",
po::value(&opt.num_passes)->default_value(2),
"How many passes of jitter solving to do, with given number of iterations in each "
"pass. For more than one pass.")
"pass.")
("rig-config", po::value(&opt.rig_config)->default_value(""),
"Assume that the cameras are acquired with a set of rigs with this configuration "
"file. The intrinsics will be read, but not the transforms between sensors, as those "
Expand Down Expand Up @@ -870,7 +870,7 @@ void jitterSolvePass(int pass,
rig::RigSet & rig,
std::vector<double> & ref_to_curr_sensor_vec) {

vw::vw_out() << "Jitter solving pass: " << pass << "\n";
vw::vw_out() << "\nJitter solving pass: " << pass << "\n";

// If some of the input cameras are frame, need to store position and
// quaternion variables for them outside the camera model.
Expand Down Expand Up @@ -1095,6 +1095,15 @@ void jitterSolvePass(int pass,
orig_cam_positions, opt_cam_positions,
cam_offsets_file);

// Resize the tri_points_vec to eliminate the anchor points that were appended.
// The number of those can be variable in each pass and those do not contribute
// to the triangulation offsets. This must be at the end.
int num_tri_points = cnet.size();
size_t tri_len = num_tri_points*NUM_XYZ_PARAMS;
if (orig_tri_points_vec.size() < tri_len || tri_points_vec.size() < tri_len)
vw_throw(ArgumentErr() << "Expecting more triangulated points.\n");
orig_tri_points_vec.resize(tri_len);
tri_points_vec.resize(tri_len);
std::string tri_offsets_file = opt.out_prefix + "-triangulation_offsets.txt";
asp::saveTriOffsetsPerCamera(opt.image_files, outliers,
orig_tri_points_vec, tri_points_vec,
Expand Down

0 comments on commit b3827c5

Please sign in to comment.