Skip to content

Commit

Permalink
A couple of bugfixes for sat_sim in special cases.
Browse files Browse the repository at this point in the history
  • Loading branch information
oleg-alexandrov committed Jul 31, 2024
1 parent 0906735 commit 28952e1
Show file tree
Hide file tree
Showing 4 changed files with 124 additions and 75 deletions.
12 changes: 6 additions & 6 deletions docs/tools/sat_sim.rst
Original file line number Diff line number Diff line change
Expand Up @@ -440,7 +440,7 @@ is defined in :numref:`rig_config`.

As an example, consider the setup from :numref:`sat_sim_roll_pitch_yaw`. Add the
rig option, and do not set the image size, focal length, and optical center on
the command line, as those are set by the rig.
the command line, as those are set by the rig configuration.

The produced image and camera file names will include the sensor name, before
the image/camera extension. Example::
Expand Down Expand Up @@ -483,7 +483,7 @@ using the option ``--save-as-csm``.
:name: sat_sim_rig_illustration
:alt: sat_sim_rig_illustration

Illustration of ``sat_sim`` creating a rig of 3 cameras. The resulting
Illustration of ``sat_sim`` creating a rig of 3 frame cameras. The resulting
images have been mapprojected onto the ground.

.. _sat_sim_time:
Expand All @@ -497,7 +497,7 @@ starting ground position (``--first-ground-pos``), and satellite velocity
recorded for each acquisition.

The time is measured in seconds in double precision. Time is important for
pointing control with a rig.
modeling a rig, when this option is set to true even when not explicitly set.

The time will be saved with the linescan camera metadata. It will be part of the
name of the pinhole cameras and images (but not part of the name for linescan
Expand All @@ -517,9 +517,9 @@ looks straight down at the starting point of the ground path. The default
value is 10,000 seconds.

For different orbits it is suggested to use a different value for
``--reference-time``. It is suggested to keep the reference time in the 10,000 -
100,000 range to ensure the produced times are positive but not too large, which
can result in loss of precision.
``--reference-time``, and also a different output prefix. It is suggested to
keep the reference time in the 1000 - 100,000 second range to ensure the produced
and nearby times are positive but not too large, which can result in loss of precision.

Here we also assumed a rig was present (:numref:`sat_sim_rig`), with the sensor
name being ``haz_cam``.
Expand Down
36 changes: 26 additions & 10 deletions src/asp/Camera/SatSim.cc
Original file line number Diff line number Diff line change
Expand Up @@ -513,19 +513,30 @@ void adjustForFrameRate(SatSimOptions const& opt,
// Number of cameras. Add 1 because we need to include the last camera.
num_cameras = int(orbit_len / period) + 1;

// Cannot have one camera sample for linescan regardless of what the user wants
bool is_linescan = (opt.sensor_type.find("linescan") != std::string::npos);

// Sanity checks. It is fine to have one single camera, but that is not usual.
if (num_cameras < 1)
vw::vw_throw(vw::ArgumentErr() << "The number of cameras must be at least 1.\n");
if (num_cameras == 1)
vw::vw_out(vw::WarningMessage) << "Warning: Creating only one camera sample.\n";

// Update the orbit length
orbit_len = period * (num_cameras - 1.0);
if (num_cameras == 1) {
if (is_linescan) {
vw::vw_out(vw::WarningMessage) << "For linescan cameras, must have at least "
"two camera samples. Adding a second one.\n";
num_cameras = 2;
} else {
vw::vw_out(vw::WarningMessage) << "Creating only one frame camera sample.\n";
}
}

// Update the orbit length. Handle gracefully the case of one camera.
orbit_len = period * std::max(num_cameras - 1.0, 1.0);

// Sanity check, important for the work below. It is fine for first and last
// proj to be in the same location, but that is not usual.
if (norm_2(last_proj - first_proj) < 1e-6)
vw::vw_out(vw::WarningMessage) << "Warning: The first and last camera positions are too close. Check your inputs.\n";
vw::vw_out(vw::WarningMessage) << "Warning: The first and last camera positions are "
<<"too close. Check your inputs.\n";

// Travel along the orbit in very small increments. Return the last point
// before exceeding the orbit length.
Expand Down Expand Up @@ -562,8 +573,10 @@ void adjustForFrameRate(SatSimOptions const& opt,

}

// Update the last orbit point, in projected coords
last_proj = out_proj;
// Update the last orbit point, in projected coords. Handle gracefully
// the case of one camera.
if (norm_2(last_proj - first_proj) > 1e-6)
last_proj = out_proj;
}

// Given the direction going from first_proj to last_proj, and knowing
Expand Down Expand Up @@ -871,6 +884,9 @@ void genCamPoses(SatSimOptions & opt,
int last_pos = opt.num_cameras; // stop before last
if (opt.sensor_type == "linescan") {
// Double the number of cameras, half of extra ones going beyond image lines
if (opt.num_cameras < 2)
vw::vw_throw(vw::ArgumentErr() << "For linescan cameras, must have at least "
"two camera samples.\n");
first_pos = -opt.num_cameras/2;
last_pos = 2 * opt.num_cameras + first_pos;
}
Expand Down Expand Up @@ -1574,11 +1590,11 @@ void genRigCamerasImages(SatSimOptions & opt,
local_opt.optical_center[1] = params.GetOpticalOffset()[1];
local_opt.image_size[0] = params.GetDistortedSize()[0];
local_opt.image_size[1] = params.GetDistortedSize()[1];
local_opt.sensor_type = sensor_types[sensor_it];
local_opt.sensor_type = sensor_types[sensor_index];

// The transform from the reference sensor to the current sensor
Eigen::Affine3d ref2sensor = rig.ref_to_cam_trans[sensor_index];
std::string suffix = "-" + sensor_names[sensor_it];
std::string suffix = "-" + rig.cam_names[sensor_index];
bool have_rig = true;
genCamerasImages(ortho_nodata_val, have_rig, sensor_index, dem, height_guess,
ortho_georef, ortho, local_opt, rig, dem_georef, suffix);
Expand Down
Loading

0 comments on commit 28952e1

Please sign in to comment.