Level 2 Help for MARSNAV2

INP

There are two options for describing input images. 

Either:
List the image file names 

Or:
provide an ascii file with the file names listed, one per record.

Note that normally only the label is used from the input images.  They
are typically image files for convenience and compatibility with marstie et al.
However, Dynamic XYZ tiepoints require the corresponding input file to be an
XYZ image.


OUT

Output navigation table, containing the updated pointing and surface model
information.  It should also contain rover localization if used, but this is
not yet implemented.

This is either an XML file, or an ASCII table, depending on the value of
FORMAT.


IN_TPT

The input tiepoint file, as generated by MARSTIE (or a previous run of
MARSNAV).  This file must be specified.  It can be in either the old text
format, or the new XML format (it detects this automatically).


OUT_TPT

The output tiepoint file, which holds changes to the tiepoints made by either
batch or interactive editing modes of MARSNAV.  This file is always written
in the new XML tiepoint format.  It can be converted to the old format using
marstie.


NAVTABLE

The optional input navigation table.  If provided, this allows the user to
provide an initial nav solution, which is then tweaked by the marsnav process.
This allows a pointing solution created by other means, (such as MICA) or via
an earlier marsnav run, to be adjusted.  This may be used to better globally
distribute error or accomodate new tiepoints, among other things.

Note that there is no guarantee the result will bear any resemblance to the
input nav file.  It is merely a starting point, and marsnav may go off in a
completely different direction.


FORMAT

The output format of navigation file.
If format=TXT, then the output is an ASCII table with a header,
then one record per input picture giving:
Number of Parameters (N), N Original Parameters, N Corrected Parameters
If images come from different instruments, the number of pointing parameters
may be different for each one.  

If format=XML, then the output is a xml file in following format:
<?xml version="1.0" encoding="UTF-8"?>
<pointing_correction ...>
   ...
  <priority>
    <entry solution_id=.../> 
  </priority>
  <solution ...>
    <image filter=... frame_id=... image_id=... instrument=...>
       <original_parameters type=...>
         <parameter id=... value=.../>
       </original_parameters>
    </image>
    <pointing_parameters type=...>
       <parameter id=... value=.../>
    </pointing_parameters>
    <camera_model type=...>
       <parameter id=... type=... value=.../>
       ...
       <reference_frame name=... index=.../>
    </camera_model>
  </solution>
  ...
</pointing_correction>


OUT_SOLUTION_ID

Solution id for the OUTPUT navigation file in XML format.
If solution id is missing when FORMAT=XML, then the output
navigation file can not be created (therefore the parameter is required).


SOLUTION_ID

Specifies which solution ID to use for the INPUT nav file (if present).

There are potentially many different definitions for the same coordinate
system. These are identified via a unique Solution ID.  If this parameter
is given, only the specified solution's definition is searched for.  Normally
it is not used.



REFIMAGE

Specifies which image (if any) are reference images.

Reference images are assumed to be correctly navigated and will not be
adjusted.

Defaults to the image with the greatest number of connected images once
tiepoints have been culled to one per pair.

REFIMAGE=-1 means no reference image.

REFIMAGE can be a single image, or a list of images.  Each image in the
list will be a reference image.  (see also UNTIL).  This allows any arbitrary
images to be selected as references.  If an image number is negative, it means
all images from the previous number through (the absolute value of) this one 
will be references.  For example a list:

1,3,-6,8,11,-15

will cause the following images to be reference imgaes:

1,3,4,5,6,8,11,12,13,14,15

Numbering of images starts at 1.


UNTIL

Means that all images from 1 to the first value of REFIMAGE inclusive are
treated as reference images.  The pointing of these will not change.  Any
additional images listed in REFIMAGE will also be reference images.

The functionality of this parameter has been subsumed by the negative number
feature of REFIMAGE.  For example, REF=5 -UNTIL is the same as REF=\(1,-5\).


IGNORE

Specifies a list of images that will be ignored.  Tiepoints containing this
image will be ignored and excluded from consideration (but see IGNORE_INTRA).
This has two purposes.  First, for very large tiepoint files, when adjusting
only a few images (via REFIMAGE), the presence of spurious tiepoints can be a
significant performance drain.  Second, this allows you to exclude a tiepoint
that is known to be problematic.  This might occur, for example, when matching
a foreground mastcam image to a background navcam image - even though the
foreground to background connections are correct, they may pull the foreground
solution out of alignment.

Ignored tiepoints still appear in the output tiepoint file (if one is written).

Ignored images should always be reference images (although this is not checked
nor enforced).  A non-reference (active) image cannot be adjusted if all
tiepoints containing that image are removed.

Like REFIMAGE, IGNORE accepts negative numbers to indicate ranges.  So a value
of 4,-7 means 4,5,6,7 are all ignored.  See REFIMAGE for more examples.


IGNORE_INTRA

This flag causes all tiepoints between non-reference (active) images to be
ignored.  Only tiepoints between non-reference and reference images will be
considered.

The use case for this is as follows:  Say you are insetting images (e.g.
mastcam on MSL) into a background (e.g. navcam) mosaic that has already been
tiepointed and nav'd.  You want to coregister the images to the background.
This flag allows you to use autotie to get a complete set of tiepoints but
then only use the ones tying the foreground to the background.  This is
beneficial because the normal autotie modes will create many more overlap
ties than full-image ties, making the overlap ties overwhelm the full-image
ties.  Since you want the full-image ties, this flag lets you ignore the
overlap ties.


ERROR

The final pixel tiepoint residual error that is permitted. Points exceeding 
this residual are candidates for removal if REMOVE is on. Default is 7 pixels.


DO_POINTING

This keyword specifies whether or not pointing should be adjusted.  It defaults
to on.  You may wish to turn off pointing correction if you were only interested
in a surface model or localization adjustment.  Note that a nav file is still 
written even if NO_POINTING is on; it simply specifies no adjustment.


DO_LOCATION

Specifies which rover locations are to be adjusted.  This changes the XYZ
location of the rover only; it does NOT adjust the rover orientation (see
DO_ORIENTATION).

When marsnav runs, it prints out a list of all sites used by the input files.
Note that a "site" in this sense is any rover position, NOT just formally a
Site frame.  This list is indexed by a single number (counting 0 to n).
DO_LOCATION is a list of these numbers specifying which of the locations to
adjust.  These are not Site indexes (e.g. as defined by MER); they are
indexes into the printed-out table.  Note that this means you must normally
run marsnav once to get this table printed, kill it, and rerun with
DO_LOCATION specified.

For example, if the following is printed:

List of Sites used by input files:
  Site 0,'MER_ROVER: (11,55,73,367,167)',count=9. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 1,'MER_ROVER: (11,55,111,396,291)',count=7. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 2,'MER_ROVER: (11,55,119,403,291)',count=23. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 3,'MER_ROVER: (11,59,0,0,0)',count=42. Adj loc=0,ori=0. match loc=-1,ori=-1

it says that 9 images use the "MER_ROVER: (11,55,73,367,167)" position, which
is called 0 in marsnav.  42 use "MER_ROVER: (11,59,0,0,0)", which is called
3, and so on.  If you wanted to adjust the last two locations, you would give
DO_LOCATION=(2,3).  Check to make sure the appropriate "adj loc" values change
to 1.

Ignore match loc at the moment.  Eventually the plan is to allow sites to
be glued together such that one value changes both, but this is not yet
implemented.

*IMPORTANT*  The results of the localization are printed to stdout.
These results are NOT written into an RMC file. They should be, but 
implementation time during ops did not allow for this.  So, you must create an 
RMC file by hand, and cut-and-paste the printed values into it. The XYZ and 
quaternion are conveniently formatted for cut-and-paste into an RMC file.

Note:  in some cases you may want to take the resulting XYZ value and use
it as a Site vector (SVF file) rather than a Rover vector (RVF).  However,
any simultaneous adjustment of positions within the same site would have to
be adjusted to account for the site offset.  Position 0 is by definition at
offset (0,0,0) to the Site, so any adjustment of Position 0 really needs to
be a Site update.  But that adjustment would not be reflected in the other
positions within the site so the value would have to be subtracted from the
other calculated positions in order to maintain consistency.



DO_ORIENTATION

Specifies which rover orientations are to be adjusted.  This changes the
Euler angles (and thus the quaternion) of the rover only; it does NOT
adjust the rover location (see DO_LOCATION).

When marsnav runs, it prints out a list of all sites used by the input files.
Note that a "site" in this sense is any rover position, NOT just formally a
Site frame.  This list is indexed by a single number (counting 0 to n).
DO_ORIENTATION is a list of these numbers specifying which of the orientations
to adjust.  These are not Site indexes (e.g. as defined by MER); they are
indexes into the printed-out table.  Note that this means you must normally
run marsnav once to get this table printed, kill it, and rerun with
DO_ORIENTATION specified.

For example, if the following is printed:

List of Sites used by input files:
  Site 0,'MER_ROVER: (11,55,73,367,167)',count=9. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 1,'MER_ROVER: (11,55,111,396,291)',count=7. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 2,'MER_ROVER: (11,55,119,403,291)',count=23. Adj loc=0,ori=0. match loc=-1,ori=-1
  Site 3,'MER_ROVER: (11,59,0,0,0)',count=42. Adj loc=0,ori=0. match loc=-1,ori=-1

it says that 9 images use the "MER_ROVER: (11,55,73,367,167)" position, which
is called 0 in marsnav.  42 use "MER_ROVER: (11,59,0,0,0)", which is called
3, and so on.  If you wanted to adjust the second and fourth orientations,
you would give DO_ORIENTATIONS=(1,3).  Check to make sure the appropriate
"adj ori" values change to 1.

Ignore match ori at the moment.  Eventually the plan is to allow sites to
be glued together such that one value changes both, but this is not yet
implemented.

*IMPORTANT*  The results of the localization are printed to stdout. These 
results are NOT written into an RMC file.  They should be, but implementation 
time during ops did not allow for this.  So, you must create an RMC file by 
hand, and cut-and-paste the printed values into it. The XYZ and quaternion are 
conveniently formatted for cut-and-paste into an RMC file.



REMOVE

If NOREMOVE is specified, the program will not remove the worst tiepoint
in batch mode.  Instead, it will simply exit with the current solution.  
The default is NOREMOVE.

This mode can be helpful when all tiepoints are known to be good.


MAX_RESIDUAL

Specifies a threshold for residuals.  Any tiepoint above this residual will be
removed during the editing process.


MAX_REMOVE

Specifies a maximum number of loops for the remove-tiepoint process.
When tiepoints are removed, the whole solution is restarted from the
beginning (so as to not be influenced by the now-gone tiepoints).  If
MAX_REMOVE is specified, it sets a limit on the number of times this
restart can happen, independent of whether the other loop termination
criteria (error or max residual) are reached.


START_KEY

Starting key number for the tiepoint file (XML format only).  Tiepoint files
contain a list of images, each of which is associated with an integer key.
Setting START_KEY to some value allows tiepoint files to be merged easily,
without the keys conflicting.  It is acceptable to have the same image in
different sections of a merged file (with different keys); they are properly
merged when read in.


PARALLEL_LIMIT

When computing XYZ from triangulation of tiepoints, it is possible to get 
tiepoints whose rays are very close to parallel (e.g. distant tiepoints, 
near the horizon). XYZ becomes very sensitive to noise when the rays are very 
close to parallel.  This parameter sets a limit on how close to parallel rays 
can be and still be considered; those tiepoints that exceed this threshold are
ignored.  The value is specified as the dot product of the two vectors, in
other words the cosine of the angle between them.  The default is 0.9999.


OMP_ON

Turns on or off parallel processing using OMP, which uses multiple cores on
a single host machine.  The default is on.  The main help describes some
environment variables that can further control parallel processing.  Note
that this program uses standard OpenMP (which is built in to the gcc/g+ compilers), so further details can be found in the OpenMP documentation.



CONFIG_PATH

A colon-separated list of directories in which to look for configuration
and calibration files.  Environment variables are allowed in the list
(and may themselves contain colon-separated lists).  The directories are
searched in order for each config/cal file when it is loaded.  This allows
multiple projectes to be supported simultaneously, and allows the user to
override any given config/cal file.  Note that the directory structure below
the directories specified in this path must match what the project expects.
For example, Mars 98 expects flat fields to be in a subdirectory named
"flat_fields" while Mars Pathfinder expects them to be directly in the
directory specified by the path (i.e. no intermediate subdirectories).


POINT_METHOD

Specifies a mission-specific pointing method to use.  Normally this
parameter is not used, in which case the "default" pointing methods
are used.  Some missions may have special, or alternate, pointing
methods available, which are indicated by this string (for example,
backlash models, using arm joint angles instead of x/y/z/az/el, etc).
A substring search is used, so multiple methods (where that makes sense)
can be specified by separating the keywords with commas.

The methods available vary per mission, but some methods available at
the time of this writing are:

BACKLASH : Mars 98 SSI only.  Selects a backlash pointing model,
which adjusts the telemetered azimuth and elevation values based on
knowledge of the camera's mechanical backlash and the direction the
motor was travelling when the image was taken.


MATCH_METHOD

Specifies a method for reading the nav file.

Loose method matches with pointing parameters of the image.
Tight method matches with unique id of the image.

Applies only to an input nav file, if given (not to the output nav file).


MATCH_TOL

Tolerance value for matching pointing parameters in the pointing corrections file.
Used if MATCH_METHOD=LOOSE
Default value is pretty arbitrary, though seems to work well so far....


RSF

Rover State File.  This is a list of filenames to load containing
Rover State information.  These files contain position and orientation
information for a rover (or other mobile spacecraft) at various sites.
They are in XML format.  See the "Rover Motion Counter (RMC) Master File SIS"
for details on these files.

Rover State Files have a priority order.  The files listed first have
the highest priority.

Environment variables may be used in the list.

For MER, if a directory is specified, then that directory is searched for
RMC Master files and any found are loaded.  The directory structure and
filename convention is covered in the RMC SIS.  The directory specified
is the one containing "master", so if <dir> is the name specified in the
RSF parameter, the following files will be searched for:

<dir>/master/_Master.svf
<dir>/master/_Site__Master.rvf

The name of each file loaded is printed to the stdout log for reference.


DEBUG_RSF

If enabled, this causes the internal database of RMC locations to be
printed out to the stdout log.  This is after the RSF files have been
loaded and the coordinate systems read from the input label(s).


COORD

This parameter is ignored by marsnav, except for one place.  It is
here for compatibility with subroutines used by other programs (see
e.g. marsmap).


COORD_INDEX

This parameter is ignored by marsnav (except in one case; see COORD).  It
is here for compatibility with subroutines used by other programs (see
e.g. marsmap).


FIXED_SITE

Specifies which major Site is the "Fixed" Site for this run.

Historically, MPF and M98 had a single "Surface Fixed" frame which never
moved, and which all other coordinate system frames were referenced to.
With the advent of long-range rovers (such as MER and FIDO), that became
insufficient.  The rover traverses far enough that errors in knowledge of
coordinate system offset and orientation become unacceptable.

For this reason, a system of major Sites was introduced.  Periodically
during the mission, a Site frame is declared.  This then becomes the
reference frame for all activities until the next Site is declared.
References are kept local, and errors don't propogate across Sites.

However, if images from more than one Site are combined together, the
Site's must be placed relative to each other.  Therefore a single reference
frame is still needed to combine different sites.

The FIXED_SITE parameter controls which of the major Site frames is
the reference ("fixed") site for this program run.  This fixed frame
can vary in different program runs, but is constant throughout one
execution.

If not specified, FIXED_SITE defaults to the minimum Site number (i.e.
lowest numbered, or earliest chronologically) used in all input images.
Normally this default is sufficient; rarely must FIXED_SITE be specified.

One or more Rover State Files must usually be specified in order to combine
image from more than one Site.  These describe the relationship between
sites.  See the RSF parameter.



DO_FILTER

Specify if the tracks are to be filtered or not before being used in the 
optimization process.
The Union-Find algorithm analyzes a list of pairwise relation (tiepoints) to 
return a list of tracks that group together all the observations (pixel)
"looking" at the same ground point. Because tie-points may contains erroneous 
pairing, some tracks might be corrupted. A corrupted track for instance is a 
track that contains two observations from the same image, i.e., two points in 
the same image that "look" at the same ground point.
If DO_FILTER, the track list is analysed for such corruption. There 
are algorithms (e.g.,Gomory-Hu tree analysis) that prune the track from bad 
observations. However, for now, if a track contains two points from  the 
same image (corruption), the track is deleted.
Note that the current approach does not remove all bad tracks. For instance,
a track with erroneous observations that are not connected to other 
observations belonging to the same image will go undetected.
Default is ON.




DISP_CONNECT

If ON, the connectivity matrix of the images will be printed to the stdout.
The connectivity matrix shows the connection of the images between each other
trough the tiepoints (or more precisely, through the tracks). The connectivity
is inferred from the track list once it's been filtered (see DO_FILTER), 
such that the matrix really respresent the connectivity that goes into the 
optimization process. This is a visually convenient way to estimate if the 
images are sufficiantly and well connected.

An example of a printed out connectivity matrix for a BA on 20 images is:

0  1  2  3  4  5  6  7  8  9 10 11 12 13 14 15 16 17 18 19
0  .  1  .  .  .  .  .  .  .  .  .  .  .  .  .  2  .  .  .
1     3  1  .  .  .  .  .  .  .  .  .  .  .  1  1  1  .  .
2        5  1  .  .  .  .  .  .  1  1  1  .  1  1  1  .  1
3           1  .  .  .  .  .  .  2  4  1  .  .  2  9  .  .
4              4  1  .  .  .  .  9 10  .  .  .  1  1  2  5
5                 3  1  .  1  1  5  .  .  .  .  1  3  2  .
6                    1  .  .  .  .  .  .  .  .  .  2  .  .
7                       .  .  1  .  .  .  .  .  .  .  .  .
8                          .  .  .  .  .  .  .  .  .  .  .
9                             1  .  1  .  .  .  .  .  .  .
10                               7  1  .  .  .  .  1  .  .
11                                  8  .  .  .  1  .  .  .
12                                     8  .  .  2  6  1  .
13                                        1  .  .  1  .  .
14                                           .  .  .  .  .
15                                              5  1  .  .
16                                                 7  1  .
17                                                    .  .
18                                                       7
19 
 
A dot (".") indicates no connection between the two images. A number 
indicates the number of connections between the two images, i.e., the number of
tracks containing both images.
For instance, we can see that image 0 is connected to image 2 and 16 only. 
Image 0 and image 2 have 1 connection, while image 0 and image 16 have 2
connections. We don't necessarily have the details of the connection, i.e., 
Image 0 for instance may be represented in a total of 3 tracks 
((0,2), (0,16), (0,16)) or 2 tracks ((0,2,16), (0,16)).
We can also see that image 8 is not connected to any image, which is not
recommended. Image 14 is only connected to image 13 trough 1 track. It's not
much and indicate where to add tiepoints if doing so.

Obviously, if the number of image is large, the printing of the connectivity
matrix will pose problem. In such case, the printing could be disabled
(NODISP_CONNECT). Note that information on disconnected block of images
is still printed in the stdout if NODISP_CONNECT.



LOSS_FUNCTION

The BA reduces to a Least Square sum minimization. The *values* that are 
squared and summed are the residuals. The underlying assumption for this 
problem layout is that the residuals distribution is more or less gaussian. 
This is generally true if the residuals are due to the standard errors, i.e.,
a combination of instrument errors and, most importantly, the standard tiepoints
error (e.g., correlation precision, manual selection precision, keypoint feature
selection precision). Usually tiepoints errors are "standard" - close to the 
pixel or at most few pixels. However, it happens (not so infrequently), that 
tiepoints may be completely bogus (correlation outlier, user misinterpretation, 
similar keypoint signatures) - tens, if not hundreds of pixels off. In that 
case, the squared residual will be very large, causing the entire solution to 
be being pulled away from the optimum.
To account for this, it is important to minimize the effect of spurious 
observations in the optimization process. It is done with a loss function.
A loss function is a function that is applied to the residual and which 
reduces the actual residual value, before being summed. The higher the residual,
the larger the reduction. For small residuals the loss function is close to the 
identity function to avoid changing *good* residuals.
There are three loss functions available:
- Trivial Loss: f(x)=x   Identity function, so no change in the residual. This 
is the default.
- Huber Loss: f(x) = x  if x<1
              f(x) = 2 sqrt(x) - 1  if x>1
- Cauchy loss: f(x) = log(1+x)
The residual reduction is strongest with Cauchy and null with Trivial. Huber
reduction is intermediate.

Note: More loss functions are available in Ceres (see documentation at
ceres-solver.org), and could be easily implemented if needed.



BOUNDS_POINT

This is a multiplicative coefficient to apply to the pointing parameters
estimated error (retrieved from getPointingErrorEstimate) to bound the 
pointing solution within a range. Pointing authorized range is set to:
initial value - error*bounds_point <---> initial value + error*bounds_point
Default is 0 in which case the pointings are not limited at all.



BOUNDS_SITE

Similar to BOUNDS_POINT except it is applied to Site (orientation and location)
parameters. Note that the same coefficient is applied to both orientation
and location parameters.



SOLVER

Tells Ceres which solver to use during the optimization. Ceres offers different
approaches to solve for the Non-Linear Least Square optimization problem. In 
our context of BA, it is most likely that we'll only use either:
- DENSE_QR: Meant for small BA, with few images and a few thousands residuals and
dense connectivity preferably. If the BA problem is too large, it will crash.
- DENSE_SCHUR: Meant for large BA problem with relatively dense connectivity. It
will also work for small BA and/or sparse connectivity. For large and sparse
BA there are more efficient (memory management and time processing) algorithms
but they do require additional librairies (cf SuiteSparse, CXSparse, or 
EigenSparse in Ceres install doc).
Default is DENSE_SCHUR.

For more information, see ceres-solver.org




SUMMARY

Which type of Ceres optimization report to print in the stdout.
- NO_SUM: Does not print any report from Ceres. This is not recommended as, at
a mimimum, it should be checked if the optimization converged
- BRIEF_SUM: A one-liner giving the convergence status, number of iterations 
ran, and the initial and final cost (residual sums).
- FULL_SUM: A several lines report display showing more information on the
optimization process.

DEFAULT is FULL_SUM.



RESIDUAL_DISP

Number of residuals to print in the stdout at the end of the optimization.
Residuals are ordered from worst to best. RESIDUAL_DISP is the number of the
first worst residuals to print. For each residual the image ID and sample/line
of the observation is also printed.
For instance, if RESIDUAL_DISP=10, then the 10 worst residuals are printed.
If RESIDUAL_DISP=0, none are printed. If RESIDUAL_DISP is negative, then all
the residuals are printed.

Residual values are in pixel, that is the distance, in pixel, between the
observation pixel location and the projected pixel location.

If REMOVE is on, then the residuals are printed at each iteration of 
REMOVE.

Default is 10.
 


APPLY_LOSS_OFF

This keyword allows to apply (or not) the loss function when computing the
residuals *for display only*. The loss function is automatically applied
during the optimization, irrespective of this parameter. However, when the 
optimization is over, the residuals are printed on the stdout 
(if RESIDUAL_DISP != 0), and the user has the possibility to apply the loss
function to the displayed residual. If turned off, the printed residuals are
the unmodified distance between the observation pixel location and the 
projected pixel location. If turned on, the printed residual is modified by
the loss function. This is, in essence, the residuals as seen by the solver. 
This can be usefull to estimate the relative contributions of each residuals
in driving the solution.

Default is OFF.



ITER_DISP

This keyword, when on, will display on the stdout an informative line
at each iteration of the solver.