Levenberg-Marquardt non-linear graph slam optimization scheme.
Current decider optimizes the graph according to the graphslam::optimize_spa_levmarq method. Refer to the latter for more details on the implementation.
tau
Definition at line 126 of file CLevMarqGSO.h.
#include <mrpt/graphslam/GSO/CLevMarqGSO.h>
Classes | |
struct | GraphVisualizationParams |
struct for holding the graph visualization-related variables in a compact form More... | |
struct | OptimizationParams |
Struct for holding the optimization-related variables in a compact form. More... | |
Public Types | |
typedef GRAPH_T::constraint_t | constraint_t |
Handy typedefs. More... | |
typedef GRAPH_T::constraint_t::type_value | pose_t |
typedef mrpt::math::CMatrixFixedNumeric< 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 |
Public Member Functions | |
CLevMarqGSO () | |
~CLevMarqGSO () | |
bool | updateState (mrpt::obs::CActionCollectionPtr action, mrpt::obs::CSensoryFramePtr observations, mrpt::obs::CObservationPtr observation) |
Generic method for fetching the incremental action/observation readings from the calling function. More... | |
void | initializeVisuals () |
Initialize visual objects in CDisplayWindow (e.g. More... | |
void | updateVisuals () |
Update the relevant visual features in CDisplayWindow. More... | |
void | notifyOfWindowEvents (const std::map< std::string, bool > &events_occurred) |
Get a list of the window events that happened since the last call. More... | |
void | loadParams (const std::string &source_fname) |
Load the necessary for the decider/optimizer configuration parameters. More... | |
void | printParams () const |
Print the problem parameters - relevant to the decider/optimizer to the screen in a unified/compact way. More... | |
void | getDescriptiveReport (std::string *report_str) const |
Fill the provided string with a detailed report of the decider/optimizer state. More... | |
bool | justFullyOptimizedGraph () const |
Used by the caller to query for possible full graph optimization on the latest optimizer run. More... | |
virtual void | setWindowManagerPtr (mrpt::graphslam::CWindowManager *win_manager) |
Fetch a CWindowManager pointer. More... | |
virtual void | setCriticalSectionPtr (mrpt::synch::CCriticalSection *graph_section) |
Fetch a mrpt::synch::CCriticalSection for locking the GRAPH_T resource. More... | |
virtual void | setGraphPtr (GRAPH_T *graph) |
Fetch the graph on which the decider/optimizer will work on. More... | |
virtual void | initializeLoggers (const std::string &name) |
Initialize the COutputLogger, CTimeLogger instances given the name of the decider/optimizer at hand. More... | |
virtual void | setClassName (const std::string &name) |
bool | isMultiRobotSlamClass () |
std::string | getClassName () const |
Public Attributes | |
OptimizationParams | opt_params |
Parameters relevant to the optimizatio nfo the graph. More... | |
GraphVisualizationParams | viz_params |
Parameters relevant to the visualization of the graph. More... | |
Protected Types | |
enum | FullOptimizationPolicy { FOP_IGNORE_LC =0, FOP_USE_LC, FOP_TOTAL_NUM } |
Enumeration that defines the behaviors towards using or ignoring a newly added loop closure to fully optimize the graph. More... | |
Protected Member Functions | |
void | _optimizeGraph (bool is_full_update=false) |
Optimize the given graph. More... | |
void | optimizeGraph () |
Wrapper around _optimizeGraph which first locks the section and then calls the _optimizeGraph method. More... | |
bool | checkForLoopClosures () |
Check if a loop closure edge was added in the graph. More... | |
bool | checkForFullOptimization () |
Decide whether to issue a full graph optimization. More... | |
void | initGraphVisualization () |
Initialize objects relateed to the Graph Visualization. More... | |
void | updateGraphVisualization () |
Called internally for updating the visualization scene for the graph building procedure. More... | |
void | toggleGraphVisualization () |
Toggle the graph visualization on and off. More... | |
void | fitGraphInView () |
Set the camera parameters of the CDisplayWindow3D so that the whole graph is viewed in the window. More... | |
void | updateOptDistanceVisualization () |
Update the position of the disk indicating the distance in which Levenberg-Marquardt graph optimization is executed. More... | |
void | toggleOptDistanceVisualization () |
toggle the optimization distance object on and off More... | |
void | getNearbyNodesOf (std::set< mrpt::utils::TNodeID > *nodes_set, const mrpt::utils::TNodeID &cur_nodeID, double distance) |
Get a list of the nodeIDs whose position is within a certain distance to the specified nodeID. More... | |
virtual void | assertVisualsVars () |
Handy function for making all the visuals assertions in a compact manner. More... | |
void | initOptDistanceVisualization () |
Initialize the Disk/Sphere used for visualizing the optimization distance. More... | |
mrpt::opengl::CRenderizablePtr | initOptDistanceVisualizationInternal (const mrpt::poses::CPose2D &p_unused) |
Setup the corresponding Disk/Sphere instance. More... | |
mrpt::opengl::CRenderizablePtr | initOptDistanceVisualizationInternal (const mrpt::poses::CPose3D &p_unused) |
Static Protected Member Functions | |
static void | levMarqFeedback (const GRAPH_T &graph, const size_t iter, const size_t max_iter, const double cur_sq_error) |
Feedback of the Levenberg-Marquardt graph optimization procedure. More... | |
Protected Attributes | |
bool | m_first_time_call |
bool | m_has_read_config |
bool | registered_new_node |
bool | m_autozoom_active |
size_t | m_last_total_num_of_nodes |
mrpt::system::TThreadHandle | m_thread_optimize |
FullOptimizationPolicy | m_optimization_policy |
Should I fully optimize the graph on loop closure? More... | |
bool | m_just_fully_optimized_graph |
Indicates whether a full graph optimization was just issued. More... | |
size_t | m_min_nodes_for_optimization |
Minimum number of nodes before we try optimizing the graph. More... | |
GRAPH_T * | m_graph |
Pointer to the graph that is under construction. More... | |
mrpt::synch::CCriticalSection * | m_graph_section |
mrpt::utils::CTimeLogger | m_time_logger |
Time logger instance. More... | |
std::string | m_class_name |
Name of the class instance. More... | |
bool | is_mr_slam_class |
Boolean indicating if the current class can be used in multi-robot SLAM operations. More... | |
Smart Full-Optimization Command | |
Instead of issuing a full optimization every time a loop closure is detected, ignore current loop closure when enough consecutive loop closures have already been utilised. This avoids the added computational cost that is needed for optimizing the graph without reducing the accuracy of the overall operation | |
size_t | m_max_used_consec_lcs |
Number of maximum cosecutive loop closures that are allowed to be issued. More... | |
size_t | m_curr_used_consec_lcs |
Number of consecutive loop closures that are currently registered. More... | |
size_t | m_max_ignored_consec_lcs |
Number of consecutive loop closures to ignore after m_max_used_consec_lcs have already been issued. More... | |
size_t | m_curr_ignored_consec_lcs |
Consecutive Loop Closures that have currently been ignored. More... | |
Visuals-related variables methods | |
mrpt::graphslam::CWindowManager * | m_win_manager |
Pointer to the CWindowManager object used to store visuals-related instances. More... | |
mrpt::gui::CDisplayWindow3D * | m_win |
Window to use. More... | |
mrpt::graphslam::CWindowObserver * | m_win_observer |
CWindowObserver object for monitoring various visual-oriented events. More... | |
bool | m_initialized_visuals |
Static Protected Attributes | |
static const std::string | header_sep = std::string(80, '-') |
Separator string to be used in debugging messages. More... | |
static const std::string | report_sep = std::string(2, '\n') |
typedef GRAPH_T::constraint_t mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::constraint_t |
Handy typedefs.
Definition at line 134 of file CLevMarqGSO.h.
typedef mrpt::graphslam::CRegistrationDeciderOrOptimizer<GRAPH_T> mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::grandpa |
Definition at line 139 of file CLevMarqGSO.h.
typedef mrpt::math::CMatrixFixedNumeric<double, constraint_t::state_length, constraint_t::state_length> mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::InfMat |
Definition at line 138 of file CLevMarqGSO.h.
typedef mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T> mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::parent |
Definition at line 140 of file CLevMarqGSO.h.
typedef GRAPH_T::constraint_t::type_value mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::pose_t |
Definition at line 135 of file CLevMarqGSO.h.
|
protected |
Enumeration that defines the behaviors towards using or ignoring a newly added loop closure to fully optimize the graph.
Enumerator | |
---|---|
FOP_IGNORE_LC | |
FOP_USE_LC | |
FOP_TOTAL_NUM |
Definition at line 354 of file CLevMarqGSO.h.
mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::CLevMarqGSO | ( | ) |
Definition at line 19 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::initializeLoggers(), MRPT_END, and MRPT_START.
mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::~CLevMarqGSO | ( | ) |
Definition at line 37 of file CLevMarqGSO_impl.h.
|
protected |
Optimize the given graph.
Wrapper around the graphslam::optimize_spa_levmarq method
[in] | full_update | Impose that method optimizes the whole graph |
Definition at line 391 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::cfg, mrpt::utils::CTimeLogger::enter(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::getNearbyNodesOf(), mrpt::utils::CTimeLogger::leave(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_just_fully_optimized_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_min_nodes_for_optimization, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_time_logger, MRPT_END, MRPT_START, MRPT_UNUSED_PARAM, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, mrpt::graphslam::optimize_graph_spa_levmarq(), mrpt::utils::CTicTac::Tac(), and mrpt::utils::CTicTac::Tic().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::optimizeGraph(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
protectedvirtualinherited |
Handy function for making all the visuals assertions in a compact manner.
Definition at line 87 of file CRegistrationDeciderOrOptimizer_impl.h.
|
protected |
Decide whether to issue a full graph optimization.
In case N consecutive full optimizations have been issued, skip some of the next as they slow down the overall execution and they don't reduce the overall error
Definition at line 499 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForLoopClosures(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::FOP_IGNORE_LC, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::FOP_USE_LC, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_curr_ignored_consec_lcs, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_curr_used_consec_lcs, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_max_ignored_consec_lcs, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_max_used_consec_lcs, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_optimization_policy, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_WARN_STREAM, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
protected |
Check if a loop closure edge was added in the graph.
Match the previously registered edges in the graph with the current. If there is a node difference in any new edge greater than LC_min_nodeid_diff (see .ini parameter) then new constraint is considered a Loop Closure
Definition at line 459 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::last_pair_nodes_to_edge, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::LC_min_nodeid_diff, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, MRPT_END, MRPT_START, and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization().
|
inlineprotected |
Set the camera parameters of the CDisplayWindow3D so that the whole graph is viewed in the window.
Definition at line 235 of file CLevMarqGSO_impl.h.
References ASSERTMSG_, mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::opengl::CGridPlaneXY::getPlaneLimits(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, MRPT_END, MRPT_START, mrpt::gui::CDisplayWindow3D::setCameraAzimuthDeg(), mrpt::gui::CDisplayWindow3D::setCameraElevationDeg(), mrpt::gui::CDisplayWindow3D::setCameraPointingToPoint(), mrpt::gui::CDisplayWindow3D::setCameraProjective(), mrpt::gui::CDisplayWindow3D::setCameraZoom(), and mrpt::gui::CDisplayWindow3D::unlockAccess3DScene().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization().
|
inlineinherited |
Definition at line 138 of file CRegistrationDeciderOrOptimizer.h.
|
virtual |
Fill the provided string with a detailed report of the decider/optimizer state.
Report should include (part of) the following:
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 649 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::getDescriptiveReport(), mrpt::utils::CTimeLogger::getStatsAsText(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::header_sep, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_time_logger, MRPT_END, MRPT_START, and mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::report_sep.
|
protected |
Get a list of the nodeIDs whose position is within a certain distance to the specified nodeID.
Definition at line 580 of file CLevMarqGSO_impl.h.
References mrpt::math::distance(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, MRPT_END, and MRPT_START.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph().
|
inlineprotected |
Initialize objects relateed to the Graph Visualization.
Definition at line 153 of file CLevMarqGSO_impl.h.
References ASSERTMSG_, mrpt::graphslam::CWindowManager::assignTextMessageParameters(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::keystroke_graph_autofit, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::keystroke_graph_toggle, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_manager, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_observer, MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::offset_y_graph, mrpt::graphslam::CWindowObserver::registerKeystroke(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::text_index_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::visualize_optimized_graph, and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initializeVisuals().
|
virtualinherited |
Initialize the COutputLogger, CTimeLogger instances given the name of the decider/optimizer at hand.
Definition at line 38 of file CRegistrationDeciderOrOptimizer_impl.h.
Referenced by mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::CICPCriteriaERD(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::CICPCriteriaNRD(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::CLevMarqGSO(), and mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::CLoopCloserERD().
|
virtual |
Initialize visual objects in CDisplayWindow (e.g.
add an object to scene).
std::exception | If the method is called without having first provided a CDisplayWindow3D* to the class instance |
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 84 of file CLevMarqGSO_impl.h.
References ASSERT_, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initGraphVisualization(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::initializeVisuals(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_has_read_config, MRPT_END, and MRPT_START.
|
protected |
Initialize the Disk/Sphere used for visualizing the optimization distance.
Definition at line 269 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::CWindowManager::addTextMessage(), mrpt::graphslam::CWindowManager::assignTextMessageParameters(), mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualizationInternal(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::keystroke_optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::keystroke_optimize_graph, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_manager, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_observer, MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::offset_y_optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance_color, mrpt::graphslam::CWindowObserver::registerKeystroke(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::text_index_optimization_distance, and mrpt::gui::CDisplayWindow3D::unlockAccess3DScene().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initializeVisuals().
|
protected |
Setup the corresponding Disk/Sphere instance.
Method overloads are used to overcome the C++ specialization restrictions
Definition at line 309 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance_color.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization().
|
protected |
Definition at line 323 of file CLevMarqGSO_impl.h.
References mrpt::utils::TColor::B, mrpt::utils::TColor::G, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance_color, and mrpt::utils::TColor::R.
|
inherited |
Definition at line 132 of file CRegistrationDeciderOrOptimizer_impl.h.
|
virtual |
Used by the caller to query for possible full graph optimization on the latest optimizer run.
Reimplemented from mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T >.
Definition at line 566 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_just_fully_optimized_graph.
|
staticprotected |
Feedback of the Levenberg-Marquardt graph optimization procedure.
Definition at line 572 of file CLevMarqGSO_impl.h.
|
virtual |
Load the necessary for the decider/optimizer configuration parameters.
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 613 of file CLevMarqGSO_impl.h.
References mrpt::utils::CLoadableOptions::loadFromConfigFileName(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::loadParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_has_read_config, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_max_ignored_consec_lcs, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_max_used_consec_lcs, MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params.
|
virtual |
Get a list of the window events that happened since the last call.
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 110 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::fitGraphInView(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::keystroke_graph_autofit, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::keystroke_graph_toggle, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::keystroke_optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::keystroke_optimize_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_autozoom_active, MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_START, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::notifyOfWindowEvents(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::toggleGraphVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::toggleOptDistanceVisualization(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params.
|
protectedvirtual |
Wrapper around _optimizeGraph which first locks the section and then calls the _optimizeGraph method.
Used in multithreaded optimization
Implements mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T >.
Definition at line 375 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::system::getCurrentThreadId(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph_section, MRPT_END, and MRPT_START.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
virtual |
Print the problem parameters - relevant to the decider/optimizer to the screen in a unified/compact way.
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 606 of file CLevMarqGSO_impl.h.
References mrpt::utils::CLoadableOptions::dumpToConsole(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::printParams(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params.
|
virtualinherited |
Definition at line 52 of file CRegistrationDeciderOrOptimizer_impl.h.
|
virtualinherited |
Fetch a mrpt::synch::CCriticalSection for locking the GRAPH_T resource.
Handy for realising multithreading in the derived classes.
Definition at line 73 of file CRegistrationDeciderOrOptimizer_impl.h.
|
virtualinherited |
Fetch the graph on which the decider/optimizer will work on.
Definition at line 124 of file CRegistrationDeciderOrOptimizer_impl.h.
|
virtualinherited |
Fetch a CWindowManager pointer.
CWindowManager instance should contain a CDisplayWindow3D* and, optionally, a CWindowObserver pointer so that interaction with the window is possible
Reimplemented in mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >.
Definition at line 61 of file CRegistrationDeciderOrOptimizer_impl.h.
|
protected |
Toggle the graph visualization on and off.
Definition at line 219 of file CLevMarqGSO_impl.h.
References mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, MRPT_END, MRPT_START, and mrpt::gui::CDisplayWindow3D::unlockAccess3DScene().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents().
|
protected |
toggle the optimization distance object on and off
Definition at line 357 of file CLevMarqGSO_impl.h.
References mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, MRPT_END, MRPT_START, and mrpt::gui::CDisplayWindow3D::unlockAccess3DScene().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents().
|
inlineprotected |
Called internally for updating the visualization scene for the graph building procedure.
Definition at line 173 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::CWindowManager::addTextMessage(), ASSERTMSG_, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::cfg, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::fitGraphInView(), mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_autozoom_active, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_manager, MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::offset_y_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::text_index_graph, mrpt::gui::CDisplayWindow3D::unlockAccess3DScene(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateVisuals().
|
inlineprotected |
Update the position of the disk indicating the distance in which Levenberg-Marquardt graph optimization is executed.
Definition at line 339 of file CLevMarqGSO_impl.h.
References ASSERTMSG_, mrpt::gui::CDisplayWindow3D::forceRepaint(), mrpt::gui::CDisplayWindow3D::get3DSceneAndLock(), mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_win_manager, MRPT_END, MRPT_START, and mrpt::gui::CDisplayWindow3D::unlockAccess3DScene().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateVisuals().
|
virtual |
Generic method for fetching the incremental action/observation readings from the calling function.
Implementations of this interface should use (part of) the specified parameters and call the optimizeGraph function if the decision is to optimize the provided graph
Implements mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T >.
Definition at line 44 of file CLevMarqGSO_impl.h.
References mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization(), mrpt::system::createThreadFromObjectMethod(), mrpt::system::joinThread(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::last_pair_nodes_to_edge, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_first_time_call, mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::m_graph, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_last_total_num_of_nodes, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::m_thread_optimize, MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_on_second_thread, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::optimizeGraph(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::registered_new_node.
|
virtual |
Update the relevant visual features in CDisplayWindow.
std::exception | If the method is called without having first provided a CDisplayWindow3D* to the class instance |
Reimplemented from mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >.
Definition at line 96 of file CLevMarqGSO_impl.h.
References MRPT_END, MRPT_START, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::optimization_distance, mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateOptDistanceVisualization(), and mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_T >::updateVisuals().
|
staticprotectedinherited |
Separator string to be used in debugging messages.
Definition at line 175 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::getDescriptiveReport(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::getDescriptiveReport().
|
protectedinherited |
Boolean indicating if the current class can be used in multi-robot SLAM operations.
Definition at line 171 of file CRegistrationDeciderOrOptimizer.h.
|
protected |
Definition at line 342 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization().
|
protectedinherited |
Name of the class instance.
Definition at line 167 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::CRegistrationDeciderOrOptimizer< GRAPH_t >::getClassName().
|
protected |
Consecutive Loop Closures that have currently been ignored.
Definition at line 393 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization().
|
protected |
Number of consecutive loop closures that are currently registered.
Definition at line 382 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization().
|
protected |
Definition at line 339 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
protectedinherited |
Pointer to the graph that is under construction.
Definition at line 146 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForLoopClosures(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::checkRegistrationCondition2D(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::checkRegistrationCondition3D(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::getNearbyNodesOf(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::getNearbyNodesOf(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::registerNewEdge(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateOptDistanceVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateState(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState(), and mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals().
|
protectedinherited |
Definition at line 147 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::optimizeGraph().
|
protected |
Definition at line 340 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initializeVisuals(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
protectedinherited |
Definition at line 161 of file CRegistrationDeciderOrOptimizer.h.
|
protected |
Indicates whether a full graph optimization was just issued.
Definition at line 399 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::justFullyOptimizedGraph().
|
protected |
Definition at line 346 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
protected |
Number of consecutive loop closures to ignore after m_max_used_consec_lcs have already been issued.
Definition at line 388 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
protected |
Number of maximum cosecutive loop closures that are allowed to be issued.
Definition at line 377 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
protected |
Minimum number of nodes before we try optimizing the graph.
Definition at line 402 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph().
|
protected |
Should I fully optimize the graph on loop closure?
Definition at line 361 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization().
|
protected |
Definition at line 349 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
protectedinherited |
Time logger instance.
Definition at line 165 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::checkRegistrationCondition2D(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::checkRegistrationCondition3D(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::getDescriptiveReport(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::getDescriptiveReport(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::initializeVisuals(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::updateState(), and mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals().
|
protectedinherited |
Window to use.
Definition at line 157 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::fitGraphInView(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::initializeVisuals(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::toggleGraphVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::toggleLaserScansVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::toggleOptDistanceVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateOptDistanceVisualization(), and mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::updateVisuals().
|
protectedinherited |
Pointer to the CWindowManager object used to store visuals-related instances.
Definition at line 155 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initGraphVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::initializeVisuals(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::toggleLaserScansVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateOptDistanceVisualization().
|
protectedinherited |
CWindowObserver object for monitoring various visual-oriented events.
Definition at line 160 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initGraphVisualization(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::initializeVisuals(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization().
OptimizationParams mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::opt_params |
Parameters relevant to the optimizatio nfo the graph.
Definition at line 227 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::_optimizeGraph(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForFullOptimization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::checkForLoopClosures(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initOptDistanceVisualizationInternal(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateVisuals().
|
protected |
Definition at line 341 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateState().
|
staticprotectedinherited |
Definition at line 176 of file CRegistrationDeciderOrOptimizer.h.
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::getDescriptiveReport(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::getDescriptiveReport().
GraphVisualizationParams mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::viz_params |
Parameters relevant to the visualization of the graph.
Definition at line 229 of file CLevMarqGSO.h.
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::initGraphVisualization(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::notifyOfWindowEvents(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::updateGraphVisualization().
Page generated by Doxygen 1.8.14 for MRPT 1.5.6 Git: 4c65e8431 Tue Apr 24 08:18:17 2018 +0200 at lun oct 28 01:35:26 CET 2019 |