Provided by: mrpt-apps_1.5.8-1_amd64 bug

NAME

       graphslam-engine - Construct and solve robot pose graphs from .rawlog dataset files

       Note:As the graphslam-engine application still under development, current manpage may be
       outdated. Refer to the MRPT doxygen class documentation and the corresponding application
       documentation for the latest features and usage instructions

SYNOPSIS

       The available command line arguments are listed below:

          graphslam-engine [--disable-visuals] [--list-optimizers]
                           [--list-regs] [--list-edge-regs]
                           [--list-node-regs][-o <CLevMarqGSO>][-e
                           <CICPCriteriaERD>][-n <CICPCriteriaNRD>][-g
                           <contents.rawlog.GT.txt>][-r <contents.rawlog>] [-i
                           <config.ini>] [--][--version] [-h]

       Alternatively run graphslam-engine -h for the full arguments list

DESCRIPTION

       Aim of the app is to perform 2D graph-slam: Robot localizes itself in the environment
       while, at the same time builds a map of that environment.  App currently executes SLAM
       using MRPT rawlog files (both MRPT rawlog formats are supported) as input which should
       contain (some of) the following observation types:

       ·   CObservationOdometry

       ·   CObservation2DRangeScan

       ·   CObservation3DRangeScan

           Working with 3DRangeScan is currently in an experimental phase.

       The majority of the graphslam-engine parameters in each case should be specified in an
       external .ini file which is to be given as a command-line argument. The following
       parameters can also be specified as command-line arguments:

       ·   .ini-file [REQUIRED]

           Specify the .ini configuration file using the -i, --ini-file flags.  Configuration
           file parameters are read by the main CGraphSlamEngine class as well as the node/edge
           registration schemes, and the optimization scheme.

       ·   rawlog-file [REQUIRED]

           Specify the rawlog dataset file using the -r, --rawlog flags.

       ·   ground-truth

           Specify a ground truth file with -g, --ground-truth flags. Ground truth has to be
           specified if user has set visualize_slam_metric or visualize_ground_truth to true in
           the .ini file, otherwise an exception is raised.

       ·   Node/Edge registration decider classes to be used.

           Specify the node registration or/and edge registration decider classes to be used
           using -n, --node-reg, -e --edge-reg flags.

           If not specified the default CFixedIntervalsNRD, CICPCriteriaERD are used as node and
           edge registration decider schemes respectively.

       ·   Optimizer class to be used

           Specify the class to be used for the optimization of the pose-graph using the -o
           --optimizer flags. Currently the only supported optimization scheme is Levenberg-
           Marquardt non-linear graph optimization defined in optimize_graph_spa_levmarq
           (http://reference.mrpt.org/devel/group__mrpt__graphslam__grp.html#ga022f4a70be5ec7c432f46374e4bb9d66)

           If not specified, the default CLevMarqGSO is used.

OPTIONS

          --disable-visuals
            Disable Visualization - Overrides related visualize* directives of the
            .ini file

          --list-optimizers
            List (all) available graphslam optimizer classes

          --list-regs
            List (all) available registration decider classes

          --list-edge-regs
            List available edge registration decider classes

          --list-node-regs
            List available node registration decider classes

          -o <CLevMarqGSO>,  --optimizer <CLevMarqGSO>
            Specify GraphSlam Optimizer

          -e <CICPCriteriaERD>,  --edge-reg <CICPCriteriaERD>
            Specify Edge registration decider

          -n <CICPCriteriaNRD>,  --node-reg <CICPCriteriaNRD>
            Specify Node registration decider

          -g <contents.rawlog.GT.txt>,  --ground-truth <contents.rawlog.GT.txt>
            Ground-truth textfile

          -r <contents.rawlog>,  --rawlog <contents.rawlog>
            Rawlog dataset file

          -i <config.ini>,  --ini_file <config.ini>
            .ini configuration file

          --,  --ignore_rest
            Ignores the rest of the labeled arguments following this flag.

          --version
            Displays version information and exits.

          -h,  --help
            Displays usage information and exits.

PROGRAM INPUT/OUTPUT

       By default graphslam-engine execution generates an output directory by the name
       "graphslam-results" within the current working directory. The output directory contains
       the following files:

       ·   CGraphSlamEngine.log

           Logfile containing the activity of the CGraphSlamEngine class instance.  Activity
           involves output logger messages, time statistics for critical parts of the
           application, and summary statistics about the constructed graph (e.g. number of
           registered nodes, edges).

       ·   node_registrar.log, edge_registrar.log, optimizer.log

           Logfiles containing the activity of the corresponding class instances. File contents
           depend on the implementation of the corresponding classes but in most cases they
           contain output logger messages, time statistics for critical parts of the class
           execution.

       ·   output_graph.graph

           File contains the constructed graph in the VERTEX/EDGE format. The latter can be
           visualized using the MRPT graph-slam application for verification reasons.

           For more information on this, see: http://www.mrpt.org/Graph-SLAM_maps
           http://www.mrpt.org/list-of-mrpt-apps/application-graph-slam/

       ·   output_scene.3DScene

           File contains the 3DScene that was generated in the end of the graphslam-engine
           execution. The latter can be visualized using the MRPT SceneViewer3D tool.

           For more information on this, see
           http://www.mrpt.org/list-of-mrpt-apps/application-sceneviewer3d/

           Note: File is generated only when the visualization of the graph construction is
           enabled in the .ini configuration file. See .ini parameters as well as the --disable
           flag for more on this.

       ·   SLAM_evaluation_metric.log

           File contains the differences between the estimated trajectory increments and the
           corresponding ground-truth increments and can be used to verify and evaluate the
           performance of the SLAM algorithm. For more information on the metric, see "A
           Comparison of SLAM Algorithms Based on a Graph of Relations - Burgard, Wolfram et al."

           Note: File is generated only when the ground-truth of the corresponding dataset is
           given.

       Note: In case a directory named graphslam-results, generated during a previous execution,
       already exists it is, by default, overwritten. If this is not the desired behavior, user
       can set the user_decides_about_output_dir .ini parameter to true so that they are asked
       about this naming conflict during program execution.

EXAMPLES

       Sample calls to the graphslam-engine application are given below:

           graphslam-engine --list-regs

           graphslam-engine --list-regs --list-optimizers

           graphslam-engine -i $mrpt/share/mrpt/config_files/graphslam-engine/odometry_2DRangeScans.ini -r $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog -g $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog.GT.txt

           graphslam-engine -i $mrpt/share//mrpt/config_files/graphslam-engine/odometry_2DRangeScans_LC_version.ini -r $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog -g $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog.GT.txt --node-reg CFixedIntervalsNRD --edge-reg CLoopCloserERD --optimizer CLevMarqGSO

           graphslam-engine -i $mrpt/share//mrpt/config_files/graphslam-engine/laser_odometry.ini -r $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog -g $mrpt/share//mrpt/datasets/graphslam-engine-demos/action_observations_map/range_030_bearing_015.rawlog.GT.txt -n CFixedIntervalsNRD -e CICPCriteriaERD

APPLICATION DESIGN

       In this section insight into the graphslam-engine application - and corresponding library
       - is provided.

       CGraphSlamEngine is the main class executing graphslam. CGraphSlamEngine delegates most of
       the graph manipulation tasks to node/edge registration deciders and optimizer classes.
       This makes up for independence between the different tasks as well as for a reconfigurable
       setup, as the user can select to use different decider/optimizer classes depending on the
       situation. Users can also write their own decider/optimizer classes by inheriting from one
       of the CNodeRegistrationDecider, CEdgeRegistrationDecider, CGraphSlamOptimizer interfaces
       depending on what part they want to implement.

   REGISTRATION DECIDERS
       The registration decider classes are divided into node and edge registration deciders. The
       former are responsible of adding new nodes in the graph while the latter add additional
       edges between already added graph nodes. These nodes can be consecutive or non-
       consecutive.

       NODE REGISTRATION DECIDERS

       Node registration decider schemes add nodes to the graph according to a specific
       criterion. Node deciders should implement the methods defined in the
       CNodeRegistrationDecider abstract class.  CNodeRegistrationDecider provides the basic
       methods that have to exist in every node registration decider class.  For an example of
       inheriting from this class see CFixedIntervalsNRD. As a naming convention, all the
       implemented node registration deciders are suffixed with the NRD acronym.

       Currently two specific node registration schemes have been implemented:

       ·   CFixedIntervalsNRD

           Decider registers a new node in the graph if the distance or the angle difference with
           regards to the previous registered node surpasses a corresponding fixed threshold.
           Decider makes use only of the CObservationOdometry instances in the rawlog file.

       ·   CICPCriteriaNRD

           Decider registers a new node in the graph if the distance or the angle difference with
           regards to the previous registered node surpasses a corresponding fixed threshold.
           Decider measures the distance from the current position to the previous registered
           node using ICP (i.e. matches the current range scan against the range scan of the
           previous node). In case of noisy 2D laser scans, decider can also use odometry
           information to locally correct and smoothen the robot trajectory. Decider makes use of
           2DRangeScans or 3DRangeScans.

       For more information on this see
       http://reference.mrpt.org/devel/classmrpt_1_1graphslam_1_1deciders_1_1_c_node_registration_decider.html

       EDGE REGISTRATION DECIDERS

       Edge registration decider schemes add edges between already added nodes in the graph
       according to a specific criterion. Edge deciders should implement the methods defined in
       CEdgeRegistrationDecider abstract class.  CEdgeRegistrationDecider provides the basic
       methods that have to exist in every edge registration decider class. For an example of
       inheriting from this class see CICPCriteriaERD. As a naming convention, all the
       implemented edge registration deciders are suffixed with the ERD acronym.

       Currently two specific edge registration schemes have been implemented:

       ·   CICPCriteriaERD

           Register new edges in the graph with the last inserted node. Criterion for adding new
           edges should be the goodness of the candidate ICP edge. The nodes for ICP are picked
           based on the distance from the last inserted node.  Decider makes use of 2DRangeScans
           or 3DRangeScans.

       ·   CLoopCloserERD

           Evaluate sets of potential loop closure edges in the graph based on their pairwise
           consistency matrix.

           Decider first splits the graph into partitions based on the 2D laser scans of the
           nodes and then searches for potential loop closure edges within the partitions. Goal
           is to register only a subset of the potential loop closure edges that maximally agree
           with each other. Decider is implemented based on the following two papers:

           [1] Consistent Observation Grouping for Generating Metric-Topological Maps that
           Improves Robot Localization - J. Blanco, J. Gonzalez, J. Antonio Fernandez Madrigal,
           2006 [2] Recognizing places using spectrally clustered local matches - E. Olson, 2009

       For more information on this see
       http://reference.mrpt.org/devel/classmrpt_1_1graphslam_1_1deciders_1_1_c_edge_registration_decider.html

   OPTIMIZERS
       Optimizer schemes optimize an already constructed graph so that the registered edges
       maximally agree with each other. Optimizer schemes should implement the methods defined in
       CGraphSlamOptimizer abstract class. For an example of inheriting from this class see
       CLevMarqGSO.

       As a naming convention, all the implemented graphslam optimizer classes are suffixed with
       the GSO acronym.

       For more information on this see
       http://reference.mrpt.org/devel/classmrpt_1_1graphslam_1_1optimizers_1_1_c_graph_slam_optimizer.html

BUGS

       Please report bugs at https://github.com/MRPT/mrpt/issues

SEE ALSO

       ·   Application wiki page - http://www.mrpt.org/Applications

       ·   mrpt::graphslam lib documentation page -
           http://reference.mrpt.org/devel/namespacemrpt_1_1graphslam.html

       ·   Application demo video - https://www.youtube.com/watch?v=Pv0yvlzrcXk

       ·   .ini Example files:

           For examples of .ini configuration files see the
           $mrpt/share/mrpt/config_files/graphslam-engine directory.  Modify $mrpt according to
           the path of MRPT source code.

       ·   Example datasets

           For a list of datasets used during the application testing see the
           $mrpt/share/mrpt/datasets/graphslam-engine directory.  Modify $mrpt according to the
           path of MRPT source code.

AUTHORS

       graphslam-engine is part of the Mobile Robot Programming Toolkit (MRPT), It was originally
       written by Nikos Koukis during the Google Summer of Code (GSOC) 2016 program.

       This manual page was written by Nikos Koukis <nickkouk@gmail.com>.

COPYRIGHT

       This program is free software; you can redistribute it and/or modify it under the terms of
       the BSD License.

       On Debian GNU/Linux systems, the complete text of the BSD License can be found in
       `/usr/share/common-licenses/BSD'.