template class mrpt::graphslam::optimizers::CLevMarqGSO

Levenberg-Marquardt non-linear graph slam optimization scheme.

#include <mrpt/graphslam/GSO/CLevMarqGSO.h>

template <class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
class CLevMarqGSO: public mrpt::graphslam::optimizers::CGraphSlamOptimizer
{
public:
    // typedefs

    typedef typename GRAPH_T::constraint_t constraint_t;
    typedef typename GRAPH_T::constraint_t::type_value pose_t;
    typedef mrpt::math::CMatrixFixed<double, constraint_t::state_length, constraint_t::state_length> InfMat;
    typedef mrpt::graphslam::CRegistrationDeciderOrOptimizer<GRAPH_T> grandpa;
    typedef mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T> parent;

    // structs

    struct GraphVisualizationParams;
    struct OptimizationParams;

    //
fields

    OptimizationParams opt_params;
    GraphVisualizationParams viz_params;

    // construction

    CLevMarqGSO();

    //
methods

    virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation);
    virtual void initializeVisuals();
    virtual void updateVisuals();
    virtual void notifyOfWindowEvents(const std::map<std::string, bool>& events_occurred);
    virtual void loadParams(const std::string& source_fname);
    virtual void printParams() const;
    virtual void getDescriptiveReport(std::string* report_str) const;
    virtual bool justFullyOptimizedGraph() const;
};

Inherited Members

public:
    // typedefs

    typedef typename GRAPH_t::constraint_t constraint_t;
    typedef typename GRAPH_t::constraint_t::type_value pose_t;

    // structs

    struct TMsg;

    //
methods

    virtual void setClassName(const std::string& name);
    bool isMultiRobotSlamClass();
    std::string getClassName() const;

Typedefs

typedef typename GRAPH_T::constraint_t constraint_t

Handy typedefs.

typedef typename GRAPH_T::constraint_t::type_value pose_t

type of underlying poses (2D/3D)

Fields

OptimizationParams opt_params

Parameters relevant to the optimizatio nfo the graph.

GraphVisualizationParams viz_params

Parameters relevant to the visualization of the graph.

Methods

virtual bool updateState(mrpt::obs::CActionCollection::Ptr action, mrpt::obs::CSensoryFrame::Ptr observations, mrpt::obs::CObservation::Ptr observation)

Generic method for fetching the incremental action-observations (or observation-only) measurements.

Returns:

True if operation was successful. Criteria for Success depend on the decider/optimizer implementing this method

virtual void initializeVisuals()

Initialize visual objects in CDisplayWindow (e.g.

add an object to scene).

Parameters:

std::exception

If the method is called without having first provided a CDisplayWindow3D* to the class instance

See also:

setWindowManagerPtr, updateVisuals

virtual void updateVisuals()

Update the relevant visual features in CDisplayWindow.

Parameters:

std::exception

If the method is called without having first provided a CDisplayWindow3D* to the class instance

See also:

setWindowManagerPtr, initializeVisuals

virtual void notifyOfWindowEvents(const std::map<std::string, bool>& events_occurred)

Get a list of the window events that happened since the last call.

virtual void loadParams(const std::string& source_fname)

Load the necessary for the decider/optimizer configuration parameters.

virtual void printParams() const

Print the problem parameters - relevant to the decider/optimizer to the screen in a unified/compact way.

virtual void getDescriptiveReport(std::string* report_str) const

Fill the provided string with a detailed report of the decider/optimizer state.

Report should include (part of) the following:

  • Timing of important methods

  • Properties fo class at the current time

  • Logging of commands until current time

virtual bool justFullyOptimizedGraph() const

Used by the caller to query for possible full graph optimization on the latest optimizer run.