Help for MARSAUTOTIE

PURPOSE:
-------

To automatically gather tiepoints for a set of overlapping images.
The resulting tiepoints are output in OUT for use by other programs
such as MARSNAV, or for manual refinement via MARSTIE.

MARSAUTOTIE supports any mission, instrument, and camera model supported
by the Planetary Image Geometry (Pig) software suite.  However, the
parameters are likely to be camera-specific, so much tuning may be
required.


EXECUTION:
---------

There are two ways to present input images:

marsautotie inp=(a.img,b.img,c.img,...) out=tiepoints.tpt
or
marstie inp=ascii_listoffiles out_tpt=tiepoints.tpt

where ascii_listoffiles is a text file containing the list of filenames
to include in the mosaic, one per record.  Up to 200 input images can be
listed.

Then use MARSNAV to generate navigation solutions, and then one of the
mosaic programs:

marsnav inp=files.lis out=mosaic.nav in_tpt=tiepoints.tpt
marsmos inp=files.lis out=mosaic.img navtable=mosaic.nav

Note: there are two tiepoint file formats; "old" is the text-based list,
while "xml" is an XML-based format.  The FORMAT parameter controls which
one to use.  Over time "old" should be phased out and eventually the FORMAT
parameter will disappear.


USAGE:
-----

It is important that all images be connected to each other via tiepoints.
If an image or block of images is not connected, the entire block can "drift"
as a unit out of alignment during the nav process.  The program will report
single unconnected images, but not blocks of them.  The "inertia" parameter
to MARSNAV can help compensate for this.

The program depends on having some initial pointing parameters in the
images, so that overlaps can be detected and tiepoints found... even though
the purpose of the program is to gather tiepoints to *correct* the pointing!
So the initial pointings (usually telemetered with the image) must be at
least somewhat close for the program to work.

The parameters likely need to be tuned; there is not yet enough experience
to say definitively what they should be.

There are many window sizes in this program:  TEMPLATE, SEARCH, SEARCH_MIN,
SEARCH_MAX, BUSY_WINDOW, PARAM_WIN.  Each of them can be specified via a
single value, which applies to both line and sample directions.  Or, they
may be specified as a pair: (line,samp), in order to define a rectangular
window.


METHOD:
------

For each input ("left" image):
   Compute a busyness metric
   Define a candidate tiepoint grid
   Get the busyest point in each grid cell
   Filter out points on the rover
   For each higher-numbered input ("right" image):
      Reject pairs that are too far apart
      Project tiepoints from left to right image
      Correlate all tiepoints
      if no tiepoints left
         Use minimum search window and correlate again
      Filter tiepoints based on correlator parameters
      Geometric scatter of points
      Store pairwise tiepoints
Save all tiepoints

Each step is detailed below, along with relevant parameters that affect
the step.  Note that throughout, for convenience, the first image of a
pair is referred to as "left" and the second as "right".  This is a
historical artifact of the correlator's roots in stereo processing, and
means absolutely nothing in terms of the relative position of the two
images in the mosaic.  The "left" image could very well be on the right.
It just means "left" is the reference, and "right" is the one searched
for matches.


Compute a busyness metric
-------------------------

This is used to determine the most interesting places to correlate on,
i.e. to make sure that there are some features that the correlator can
lock on to.  This also helps to avoid uninteresting areas such as
undifferentiated sand and sky.

The busyness metric is computed by comparing each pixel with its immediate
right and down neighbors (via absolute value of the difference), and
summing that across a window surrounding the pixel.  (algorithm courtesy
of Jean Lorre).

The BUSY_WINDOW parameter controls the size of the window over which the
busyness is computed.  As with the other windows, rectangular windows are
possible (line,samp order).  Note that the busyness values are dependent
on the window size (i.e. the larger the window, the higher the busyness
value), so when the window is adjusted, the BUSY threshold should also be
adjusted.  The metric is also sensitive to the overall brightness of the
image, and thus the proper threshold may vary per camera or even by mosaic.

Ideally, the busy window should be the same size as the correlation template
(TEMPLATE parameter).  However, the algorithm is currently implemented in
an inefficient manner (sliding sums should be used) and a window the size
of the template can be prohibitively expensive.


Define a candidate tiepoint grid
--------------------------------

A grid is defined over the image.  Each grid cell will potentially contribute
a single tiepoint.  The extent of the grid is defined by using the hard
borders as returned by PIG (FileModel.getImageBorders), combined with the
BORDER parameter and half the template size on all edges (this allows extra
slop for rotating the template).  The grid spacing is specified by (surprise!)
GRID_SPACING.


Get the busyest point in each grid cell
---------------------------------------

Within each grid cell, the pixel with the highest busyness metric is
determined.  If this value exceeds the busyness threshold (BUSY parameter),
the pixel is saved as a candidate tiepoint.  Note that the busyness
metric is somewhat unstable and thus the threshold may have to be adjusted
(see the computation section above).


Filter out points on the rover
------------------------------

This is an optional step which is enabled via the "DO_MASK" keyword value.
The points are filtered out using a rover filter, which is the same concept
as that used by the MARSFILTER program (the same subroutines are used).
This takes out most of the points that would be on the rover; presumably
any stragglers should be taken out by the parameter filter step.

Note that a different mask file is used than that typically used by
MARSFILTER.  That is because this program really should only use projected
mask shapes (ProjectedTriangle); image space masks are unlikely to be
useful and volume-based shapes are not supported (as no XYZ data is available
to this program).  A ProjectedHorizon could be used but probably should not
(especially if the horizon algorithm is ever implemented).

The mask file must be specified via the MASK parameter.  In the future this
file may be automatically loaded via the PIG library from the config directory,
but this is not yet implemented.  Nevertheless, that is a good place to
store the files.

A common use case for MSL is to run MSLFILTER on the input list to get a
mask covering the actual articulation states of the rover, and providing that
to MARSAUTOTIE to avoid all points on the rover.


Reject pairs that are too far apart
-----------------------------------

The "pointing" of the cameras (not really, but it's what getCameraOrientation()
returns) for the pair is compared.  If the angle between them is too great,
the pair is rejected as not having any potential overlap.  This is both for
efficiency, and to get around certain issues that sometimes occur with the
camera models (CAHVOR especially) when projecting well off the image.

The allowed separation is specified by SEP_ANGLE.  This could be computed from
the camera FOV, but currently is not.


Project tiepoints from left to right image
------------------------------------------

Each potential tiepoint from the left image is projected onto the surface
model, and then back-projected into the right image (a la the mosaic programs,
like MARSMAP).  This gives an initial tiepoint position on the right side
using the camera models.

Note that the surface model is used for this step.  If the surface model is
significantly wrong (or for that matter, if the pointing is too poor), the
projection may be far enough off that the correlator can't find a match.  This
problem has not been observed in testing yet, but if it is, a multipass
approach could in principle be used, with MARSNAV generating an initial
surface (and pointing), then submitting those to another run of MARSAUTOTIE.
The surface model is also used for the rover filtering, but not by any other
part of this program.

The projected tiepoint is checked to make sure it is within the right image.
Potentially a "slop" factor could be added here (to allow the point to be
slightly off the edge, for really bad pointing) but that is not implemented.

In addition to projecting the point itself, a second point, a few pixels
over horizontally, is projected as well.  This is used to determine the
nominal frame rotation angle and scale between the images at that point
(the angle changes throughout the image).  The angle and scale are used by
the correlator as an initial condition; see below.


Correlate all tiepoints
-----------------------

Each tiepoint is then correlated to find its match.  This is a multi-stage
process.  Fundamentally, a patch surrounding the point on the left image
(TEMPLATE specifies the window size) is used to look for a matching area on
the right within a search window, which is centered on the projected right
side of the tiepoint as an initial location (possibly modified by edge
effects).  The search window is dynamically adjusted, as described below,
but starts off at a size specified by SEARCH (or SEARCH_MIN, if this process
is repeated).

The first step is to do a linear correlation (GRUEN mode 0).  This allows a
match to be found quickly over a large search area.  The results are then
refined using amoeba8 (GRUEN mode 7).

For the linear correlation, the template is rotated and scaled by the frame
rotation and scale factor computed during projection.  This effectively
removes the rotation and scale difference, which greatly improves match success.

The search window is then determined.  Nominally this is centered over the
projected right-side tiepoint.  However, if the tiepoint is too close to
the edge, the search window is truncated to the edge.  For example, if the
search window is 101 pixels, a projected pixel right on the edge would be
allowed, extending half the search (50 pixels) on one side, and 0 on the
other.  This allows large search windows to still find points close to the
edge.  There is a limit to this however; the projected pixel must be at
least half of SEARCH_MIN away from the edge of the image or the point is
rejected.

A linear correlation is then performed.  The resulting quality must meet or
exceed LINEAR_QUALITY or the point is rejected.  It is generally a good idea
to have a lower quality setting for the linear case than for the amoeba case,
to handle cases like the frame rotation being inaccurate.

The correlation is then run again using the amoeba8 (8 degrees-of-freedom)
mode.  However, the correlation uses the *original* template, not the
rotated/scaled one.  The initial conditions for gruen are set to incorporate
the rotation angle and scale factor, as well as the location of the match as
returned by the linear step.  Using the original, unrotated template reduces
interpolation noise and gives GRUEN more flexibility to refine the angle.

The resulting correlation quality must meet or exceed QUALTIY, or the point
is rejected.

The final transform terms - all 8 of them - are saved for later use in the
parameter filtering step.  However, the nominal rotation and scale are backed
out from these parameters, in order to make the filtering easier.

Finally, the search window is dynamically adjusted.  This has no effect on
the tiepoint just determined, but is used for the next tiepoint (tiepoints
are processed in order according to the grid, which generally marches from
top to bottom of the image).  The dynamic adjustment allows for a wide search
area in cases where it is needed (such as when the projection is way off),
but still keeps the search size under control to some extent (which greatly
improves efficiency, and helps to reduce false matches).

The dynamic tuning is controlled by the search_edge parameter.  The delta
position is computed by subtracting the final correlated location on the
right side from the initial position.  This is then compared to the size of
the search window (really, the search minus template, divided by two - the
true "wiggle room" for template placement).  If this position is "close" to
zero (meaning the predicted position was accurate), the search window is
decreased.  If the position is "close" to the edge of the search area, then
the window is increased.  "Close" is defined via the SEARCH_EDGE parameter.
If the value is 0.3, then "close" means 30% of the total wiggle room on either
side.

If the window needs to be adjusted, then it is multiplied (to increase), or
divided (to decrease) by SEARCH_FACTOR.  SEARCH_MIN and SEARCH_MAX are used
to constrain the window size.

Note that this process happens independently in both directions (horizontal
and vertical).  It is quite possible to increase one dimension while decreasing
the other.


if no tiepoints left
 Use minimum search window and correlate again
----------------------------------------------

If after the correlation process there are no tiepoints left, it is possible
that the search window was too big for the overlap.  In that case, the
projection and correlation steps are run again, using SEARCH_MIN as the
initial search window size rather than SEARCH.

It may be that this step is now unnecessary, since the search window shaping
and dynamic adjustment were added.  That would however require some additional
analysis to prove, which is not worthwhile as of this writing.


Filter tiepoints based on correlator parameters
-----------------------------------------------

This step is really the heart of the program.  The idea is to throw out
outlier tiepoints - those whose projection parameters are statistically
dissimilar to the neighboring points.  This helps to reject bad correlations
(such as horizon mismatches or shadows that move), as well as tiepoints that
are significantly off the general trend (such as on top of a large rock, or
a stray point on the rover itself).  Experience tiepointing MER images shows
that points that are off the general trend should be avoided, as the reason
they are off the trend is usually due to uncorrectable parallax.  Correcting
the trend is much more profitable, and minimizes seams overall.

Filtering for each tiepoint is accomplished by considering an area around the
tiepoint (in pixel space), defined by PARAM_WIN, and finding all the active
tiepoints within that region.  The mean and standard deviation of each
transform coefficient are then computed.  These coefficients come straight
out of GRUEN, modified by the rotation angle and scale factor as described
above.  They represent the geometric transform (affine plus xy terms) needed
to make the template match the right side.

If there are insufficient other tiepoints available to compute meaningful
statistics (the minimum is currently hardcoded as 3), the point is rejected.

Finally, the values for each coefficient are compared against the statistics.
For the mean, if the difference is greater than that specified by PARAM_ABS,
the point is rejected.  Standard deviation is a bit more complicated.  If the
computed standard deviation is too small (less than PARAM_MIN), then the
point is accepted (this avoids rejecting points when most everything is good).
Otherwise, if the difference from the mean is greater than or equal to the
sigma value times PARAM_SIGMA, then the point is rejected.

In other words, we accept variances from the mean up to PARAM_SIGMA standard
deviations, unless the computed stdev is too small to bother with.  And the
variance must also be within an absolute limit.

When computing statistics, we consider all points that were active at the
time the filtering started, i.e. we include points that are rejected, when
computing statistics for later points.  While this sounds odd at first, it
helps solve two problems.  First, when the correlations are questionable and
many are being rejected, it is quite possible to run out of points with which
to do statistics at the bottom of the image (because everything above has been
rejected).  Even if they don't run out, the statistics get skewed towards the
bottom tiepoints, which would end up almost always being accepted.  Second,
it helps with the bimodal problem.  When there are two populations, as often
occurs with the ground and rover deck, then the first population could be
completely filtered out, leaving the second unmolested.  Since the second
is typically not what we want (being on the rover deck), considering all the
points helps to reject them.  (the rover mask is not perfect, after all).

Properly tuning the PARAM_WIN, PARAM_SIGMA, PARAM_MIN, and PARAM_ABS
parameters has to be one of the hardest and most tedious parts of using
this program.  More experience must be gained before a good parameter set
that applies to many cases can be determined.  To give a starting point,
initial tests have shown the following parameters to work for the MER
Spirit Pancam:

PARAM_SIGMA=\( 1.0, 1.0, 1.2, 1.0, 1.0, 1.0, 1.2, 1.0 \)
PARAM_MIN=\( .076, .030, 1.0, .01, .030, .076, 1.0, .01 \)
PARAM_WIN=500

And the following worked for the MER Spirit Navcam:

PARAM_SIGMA=\( 1.5, 1.5, 1.2, 1.0, 1.5, 1.5, 1.2, 1.0 \)
PARAM_MIN=\( .076, .030, 1.0, .01, .030, .076, 1.0, .01 \)
PARAM_WIN=\( 150, 300 \)


Geometric scatter of points
---------------------------

The final significant step is to take the set of tiepoints determined above,
and pare them down for use in MARSNAV.  MER experience shows that 3-4 tiepoints
per edge works reasonably well.  Tiepoints should be as close as possible to
the edge of the image that is on top in the mosaic (first in the image list),
and they should be well separated from each other.  This is achieved by
selecting a few tiepoints to survive out of the results of all of the above.

It is assumed by this point that all surviving tiepoints are "good", in that
any of them could profitably be used.  Thus, the quality of the points is not
considered; only their location within the (left) image is.  Note that by
virtue of how the loops work, the left image will always be the one first in
the list, and thus the one on top in the mosaic.

The first thing to determine is how many tiepoints to keep.  This is computed
by determining the min and max extents of the bounding box surrounding all
tiepoints.  The diagonal distance across this box is then computed, as a
rough estimate of how long the "line" of tiepoints is that covers the overlap
area.  The DENSITY parameter is then used to compute the number of tiepoints,
by dividing it into the overlap length.  Thus if the tiepoints extend all along
an edge-to-edge overlap, many more will be selected than if the tiepoints are
all concentrated in one area, or if it is a corner overlap.  Note that a
minimum of one tiepoint is kept, regardless.  The kept tiepoints are referred
to below as "candidates".

Next, the geometric center of all the tiepoints is computed (just by averaging
their line and sample coordinates).  We find the tiepoint closest to the
center, which is used to initialize all of the candidates.

We then loop over each candidate, looking to find the best tiepoint to replace
it with.  Each tiepoint is then considered, by calculating its distance from
all other candidates, and find the one that is farthest away from all the other
candidates.  We overemphasize close distances to make sure things spread out.
So instead of computing max(sum(sqrt(d2))), we do min(sum(1/d2)) (where d2 is
the Cartesian distance, squared).  We also include a factor weighting the
distance away from the center of the image (this ensures our points hug the
edge).  This weighting is controlled by CENTER_WEIGHT, and is computed as
CENTER_WEIGHT/d2.  Basically a value of 5 for CENTER_WEIGHT means that there
are 5 virtual tiepoints at the center of the image, repelling all other
tiepoints.

The tiepoint that is farthest away from the others is chosen as the new value
for that candidate slot, and the next slot is computed in the same way.

This entire process iterates until it converges (no more candidate slots
change), or MAX_ITER is exceeded (at which point, whatever is in the candidate
slots is kept).


Saving tiepoints
----------------

The survivors from the geometric scatter process are stored away as the
tiepoints for that pair.  After all pairs are considered, the entire set is
written out to the output tiepoint file.


TUNING:
------

Tuning parameters for this program can be tricky.  The DEBUG parameter can
be of assistance here.  Set it to a number between 0 and 3 to control the
amount of information printed out.

0 = no debug.  There is still a fair amount of information printed out
to the log.

1 = Print info about dynamic search window adjustment, and the culling
(geometric scatter) process.

2 = Everything from 1, plus info about the tiepoints and parameter filtering.
This is probably the most useful.  Each putative tiepoint is printed out,
along with its transform parameters.  During the filtering step, the statistics
for each tiepoint is also printed, along with a code at the end saying why it
was rejected (e.g. R6 for Relative (sigma) on parameter 6, or A2 for Absolute
on parameter 2).  A summary of the number of points rejected for each reason
is also printed for each image pair.

3 = Everything from 2, plus temporary images are saved throughout the process
showing the locations of surviving tiepoints at several steps.  This should
only be used with one or two pairs, as a LOT of images end up being saved.
One of the images is the busyness image, which can help in setting the busyness
threshold.  The images all start with "tmp".  Identifying which is which is
beyond the scope of this help; look at the source code.  However, there are
images indicating the initial points with rotation, projected points,
correlated points before filtering, and after filtering, usually on both the
left and right images.


Multiple Image Resolutions
--------------------------

Marsautotie can handle inputs at different resolutions.  For example, thumbnail
images, or combinations like Mastcam-100, Mastcam-34, and Navcam (MSL).
However, there are a few considerations when mixing images.

The program will automatically detect the scale difference (as well as rotation)
and apply that as initial conditions when doing correlation, as described
above.  However, there are limits to this.  For example, if the scale
difference was a factor of 8, and the correlation window was 9 pixels, there
wouldn't be much left to correlate.  Conversely, if the scaling happens the
other direction, the correlation window might be 72 pixels (with a corresponding
performance hit).  This should be taken into account when setting the
parameters.  One way to mitigate that somewhat is to take advantage of the
natural ordering in marsautotie; the "left" image will be the one closer to
the front of the list while the "right" one is at the back.  The left image
is the one that is scaled and rotated.

The GRID_SPACING and DENSITY parameters are measured in pixels, but naturally
relate to the image as a whole.  Therefore when presented with different
resolution images, the spacing and density may not be optimal.  That is the
purpose of the NOMINAL_HEIGHT parameter: the grid spacing and density are
scaled by the ratio of the nominal height to the actual height of each image.
So if you set a grid spacing such that you'd get 10 grid points across an image,
NOMINAL_HEIGHT will ensure you'll get 10 points across the thumbnail as well,
even though they'll be much closer together.  An open question is whether this
nominal height ratio should be applied to other pixel-dimensioned quantities,
such as correlation size (see discussion in previous paragraph).

Finally, it is sometimes the case that the difference in resolution is too
great for the linear correlator to deal with, even with the compensations
described above.  The second-stage (2-D) correlator is much more equipped to
handle these differences.  In this case it could be helpful to set the linear
correlation quality threshold (LINEAR_QUALITY) very low (0 effectively disables
it), passing all points through to the 2-D correlator.

EXAMPLES:
--------

MER Spirit pancam:

$MARSLIB/marsautotie mcmurdo_ilf_L2.lis mcmurdo_ilf_L2.tie grid_sp=15 sep=20 -do_mask mask=MER2_autotie_filter.xml param_sigma=\( 1.0, 1.0, 1.2, 1.0, 1.0, 1.0, 1.2, 1.0 \)

MER Spirit navcam:

$MARSLIB/marsautotie 2NN755ILFAOCYLC6P0605L000M2.LIS 2NN755ILFAOCYLC6P0605L000M2.tie grid_sp=15 sep=60 -do_mask mask=MER2_autotie_filter.xml param_win=\(150,300\) linear_q=0.75 busy=150 density=150 templ=15 search_min=59 q=.9


Parallel Processing
-------------------
This program has been parallelized using Open MP (OMP), which is built in
to the g++ compiler.

By default the number of threads used equals the number of cores on the machine
where the program is being run.  Each candidate in the correlation loop is
run in parallel.  Unfortunately, the dynamic adjustment of the search window
is fundamentally a serial thing - we adjust it at each tiepoint to affect the
next tiepoint.  And the dynamic adjustment is critical for performance; it
can have a 10x or better impact on runtimes.

After careful consideration, it was realized that the *timing* of the window
adjustment algorithm is not critical - it does not have to strictly affect the
next tiepoint, just future tiepoints, in order to be effective.  Therefore, the
window is adjusted as necessary, but that new window is picked up by the next
iteration to start - existing parallel iterations are not affected.  This works
well from a performance standpoint, but has the unfortunate side-effect of
making the results somewhat non-deterministic, as the tiepoints that are
affected by the update depend on what's been processed already, which is
unpredictable.  Use of dynamic scheduling means that each thread when it's
ready for more work will pick up the next iteration in order, which helps
mitigate the nondeterministic effect somewhat.  Note that you can get
deterministic behavior by setting SEARCH_EDGE to 0, effectively disabling the
window adjustment algorithm, without having to disable OMP.  If you do disable
OMP, the algorithm devolves to the original serial algorithm, and you should
again get deterministic results (although the results may differ from the
omp_on + search_edge=0 case).

The busyness computation is also parallelized (per line).

Parallel processing can be disabled via the -OMP_OFF keyword.  The number
of threads can be controlled by setting the OMP_NUM_THREADS environment
variable before running the program.  There are numerous other OMP variables
that can be set; see the OMP documentation.  However, the number of threads
is the only one that is likely to be useful in most cases.


TO DO LIST:
----------

* Use moving box for busyness calculation for efficiency.
* Consider using Gary Yagi's horizon mask routines.
* More parameter tuning!!
* Fix rover filter to compensate for CAHVOR bug (see method comments).
* Use PIG to find filter file in the config dir automatically.
* Compute appropriate SEP_ANGLE based on camera FOV.
* Once parameter sets stabilize, perhaps have "sets" you can choose from
  for different cameras (rather than setting dozens of params).
* More adaptable algorithms for parameters... for example, increasing
  window size when there's not enough information to correlate properly.
* Do something more to avoid line problems (e.g. horizon, shadows) where
  the correlation is unconstrained in one direction.
* Add some "slop" for on-image checks when projecting to the right side.
* Determine if the "correlate again using min search window" step is really
  useful any more, now that the search window shaping and adjustment is done.


HISTORY:
-------

1994-04-30 J Lorre - Initial mpfnav
1998-09    B. Deen - Multimission conversion
1999-07    ??? - Split of original MARSNAV into two parts:  MARSTIE and MARSNAV
2006-09    rgd - Wrote MARSAUTOTIE using MARSTIE as a base
2013-04-02 rgd - Changes to work with multiple resolution inputs
2016-10-18 rgd - Parallelization of code
2020-02-18 wlb - IDS-7927 - replaced sprintf() calls with snprintf() calls; removed unused variables.

COGNIZANT PROGRAMMER:  Bob Deen


PARAMETERS:


INP

Input image(s) or file list.

OUT

Output tiepoint file.

NAVTABLE

Corrected navigation filename.

BAND

The vicar image band number. Defaults to 1

TEMPLATE

correlation size.

SEARCH

correlation search area.

QUALITY

Minimum acceptable correlation quality.

BORDER

Pixels to avoid on picture border.

BUSY

Threshold for busyness metric.

GRID_SPACING

Spacing for initial tiepoint grid.

SEP_ANGLE

Max separation angle for image pairs.

SEARCH_EDGE

Dynamic search window tuning: how close to edge.

SEARCH_FACTOR

Dynamic search window tuning: how much to adjust.

SEARCH_MIN

Minimum search window size.

SEARCH_MAX

Maximum search window size.

BUSY_WINDOW

Size of window for busyness metric calculation.

LINEAR_QUALITY

Quality threshold for linear correlation.

MASK

File to use specifying rover mask.

USE_MASK

Enables use of rover mask.

DENSITY

Controls how many tiepoints to keep per pair.

MAX_ITER

Max iterations for geometric scatter step.

CENTER_WEIGHT

Weighting factor for center of image in geometric scatter.

PARAM_WIN

Window size for parameter filtering.

PARAM_SIGMA

Allowed sigma for parameter filtering.

PARAM_MIN

Minimum sigma value for parameter filtering.

PARAM_ABS

Absolute difference value for parameter filtering.

DEBUG

Flag to enable debug prints and files.

START_KEY

Starting key number for tiepoint file (XML format only).

FORMAT

OLD or XML tiepoint file format.

NOMINAL_HEIGHT

Nominal height of input images.

REFIMAGE

Specifies reference images.

FOV

Overrides FOV limit for projection

OMP_ON

Turns on or off parallel processing (default: on)

NORMAL

Surface normal vector.

GROUND

Surface ground point.

SURF_COORD

Coordinate system used to define surface parameters.

SURFACE

The type of mars surface to use. INFINITY, PLANE, SPHERE1, SPHERE2, MESH.

SURF_MESH

Mesh file for surface model VARI SURF_CSFILE File containing CS for surface model

CONFIG_PATH

Path used to find configuration/calibration files.

POINT_METHOD

Specifies a mission- specific pointing method to use

MATCH_METHOD

Specifies a method for pointing corrections.

MATCH_TOL

Tolerance value for matching pointing params in pointing corrections file.

NOSITE

Disables coordinate system sites.

RSF

Rover State File(s) to use.

DEBUG_RSF

Turns on debugging of RSF parameter.

COORD

Coordinate system to use. Ignored by marstie.

COORD_INDEX

Coordinate system index for some COORD/mission combos. Ignored by marstie.

FIXED_SITE

Which site is FIXED for rover missions.

See Examples:


Cognizant Programmer: