Main file for the GraphSlamEngine.
Given a dataset of measurements build a graph of nodes (keyframes) and constraints (edges) and solve it to find an estimation of the actual robot trajectory.
// TODO - change this description The template arguments are listed below:
Definition at line 154 of file CGraphSlamEngine.h.
#include <mrpt/graphslam/CGraphSlamEngine.h>
Classes | |
struct | TRGBDInfoFileParams |
Struct responsible for keeping the parameters of the .info file in RGBD related datasets. More... | |
Public Types | |
using | fstreams_out = std::map< std::string, mrpt::io::CFileOutputStream > |
Handy typedefs. More... | |
using | fstreams_out_it = typename fstreams_out::iterator |
Map for iterating over output file streams. More... | |
using | constraint_t = typename GRAPH_T::constraint_t |
Type of graph constraints. More... | |
using | pose_t = typename GRAPH_T::constraint_t::type_value |
Type of underlying poses (2D/3D). More... | |
using | global_pose_t = typename GRAPH_T::global_pose_t |
using | nodes_to_scans2D_t = std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > |
Public Member Functions | |
CGraphSlamEngine (const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=NULL, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=NULL, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=NULL, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=NULL) | |
Constructor of CGraphSlamEngine class template. More... | |
virtual | ~CGraphSlamEngine () |
Default Destructor. More... | |
global_pose_t | getCurrentRobotPosEstimation () const |
Query CGraphSlamEngine instance for the current estimated robot position. More... | |
virtual GRAPH_T::global_poses_t | getRobotEstimatedTrajectory () const |
virtual void | getNodeIDsOfEstimatedTrajectory (std::set< mrpt::graphs::TNodeID > *nodes_set) const |
Return the list of nodeIDs which make up robot trajectory. More... | |
void | saveGraph (const std::string *fname_in=nullptr) const |
Wrapper method around the GRAPH_T::saveToTextFile method. More... | |
void | save3DScene (const std::string *fname_in=nullptr) const |
Wrapper method around the COpenGLScene::saveToFile method. More... | |
void | loadParams (const std::string &fname) |
Read the configuration variables from the .ini file specified by the user. More... | |
void | getParamsAsString (std::string *params_out) const |
Fill in the provided string with the class configuration parameters. More... | |
std::string | getParamsAsString () const |
Wrapper around getParamsAsString. More... | |
void | printParams () const |
Print the problem parameters to the console for verification. More... | |
bool | execGraphSlamStep (mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry) |
Wrapper method around _execGraphSlamStep. More... | |
virtual bool | _execGraphSlamStep (mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry) |
Main class method responsible for parsing each measurement and for executing graphSLAM. More... | |
const GRAPH_T & | getGraph () const |
Return a reference to the underlying GRAPH_T instance. More... | |
std::string | getRawlogFname () |
Return the filename of the used rawlog file. More... | |
void | generateReportFiles (const std::string &output_dir_fname_in) |
Generate and write to a corresponding report for each of the respective self/decider/optimizer classes. More... | |
void | getDeformationEnergyVector (std::vector< double > *vec_out) const |
Fill the given vector with the deformation energy values computed for the SLAM evaluation metric. More... | |
bool | getGraphSlamStats (std::map< std::string, int > *node_stats, std::map< std::string, int > *edge_stats, mrpt::system::TTimeStamp *timestamp=NULL) |
Fill the given maps with stats regarding the overall execution of graphslam. More... | |
Map computation and acquisition methods | |
Fill the given map based on the observations that have been recorded so far. | |
void | getMap (mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const |
void | getMap (mrpt::maps::COctoMap::Ptr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const |
void | computeMap () const |
Compute the map of the environment based on the recorded measurements. More... | |
pause/resume execution | |
bool | isPaused () const |
void | togglePause () |
void | resumeExec () const |
void | pauseExec () |
Static Public Member Functions | |
ground-truth parsing methods | |
static void | readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL) |
Parse the ground truth .txt file and fill in the corresponding gt_poses vector. More... | |
static void | readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose3D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL) |
static void | readGTFileRGBD_TUM (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL) |
Parse the ground truth .txt file and fill in the corresponding m_GT_poses vector. More... | |
Static Public Attributes | |
static mrpt::system::TConsoleColor | logging_levels_to_colors [NUMBER_OF_VERBOSITY_LEVELS] |
Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor. More... | |
static std::string | logging_levels_to_names [NUMBER_OF_VERBOSITY_LEVELS] |
Map from VerbosityLevels to their corresponding names. More... | |
Protected Member Functions | |
void | initClass () |
General initialization method to call from the Class Constructors. More... | |
void | initResultsFile (const std::string &fname) |
Automate the creation and initialization of a results file relevant to the application. More... | |
void | getDescriptiveReport (std::string *report_str) const |
Fill the provided string with a detailed report of the class state. More... | |
void | initCurrPosViewport () |
void | initGTVisualization () |
void | initOdometryVisualization () |
void | initEstimatedTrajectoryVisualization () |
void | initSlamMetricVisualization () |
void | decimateLaserScan (mrpt::obs::CObservation2DRangeScan &laser_scan_in, mrpt::obs::CObservation2DRangeScan *laser_scan_out, const int keep_every_n_entries=2) |
Cut down on the size of the given laser scan. More... | |
void | alignOpticalWithMRPTFrame () |
void | queryObserverForEvents () |
Query the observer instance for any user events. More... | |
void | computeSlamMetric (mrpt::graphs::TNodeID nodeID, size_t gt_index) |
Compare the SLAM result (estimated trajectory) with the GT path. More... | |
void | dumpVisibilityErrorMsg (std::string viz_flag, int sleep_time=500) |
Wrapper method that used for printing error messages in a consistent manner. More... | |
mrpt::opengl::CSetOfObjects::Ptr | setCurrentPositionModel (const std::string &model_name, const mrpt::img::TColor &model_color=mrpt::img::TColor(0, 0, 0), const size_t model_size=1, const pose_t &init_pose=pose_t()) |
Set the opengl model that indicates the latest position of the trajectory at hand. More... | |
virtual void | monitorNodeRegistration (bool registered=false, std::string class_name="Class") |
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception. More... | |
void | execDijkstraNodesEstimation () |
Wrapper around the GRAPH_T::dijkstra_nodes_estimate. More... | |
Initialization of Visuals | |
Methods used for initializing various visualization features relevant to the application at hand. If the visual feature is specified by the user (via the .ini file) and if it is relevant to the application then the corresponding method is called in the initClass class method | |
void | initVisualization () |
void | initRangeImageViewport () |
void | initIntensityImageViewport () |
mrpt::opengl::CSetOfObjects::Ptr | initRobotModelVisualization () |
mrpt::opengl::CSetOfObjects::Ptr | initRobotModelVisualizationInternal (const mrpt::poses::CPose2D &p_unused) |
Method to help overcome the partial template specialization restriction of C++. More... | |
mrpt::opengl::CSetOfObjects::Ptr | initRobotModelVisualizationInternal (const mrpt::poses::CPose3D &p_unused) |
Update of Visuals | |
Methods used for updating various visualization features relevant to the application at hand. If relevant to the application at hand update is periodically scheduled inside the execGraphSlam method | |
void | updateAllVisuals () |
Wrapper around the deciders/optimizer updateVisuals methods. More... | |
void | updateRangeImageViewport () |
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport. More... | |
void | updateIntensityImageViewport () |
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport. More... | |
virtual void | updateCurrPosViewport () |
Update the viewport responsible for displaying the graph-building procedure in the estimated position of the robot. More... | |
virtual mrpt::poses::CPose3D | getLSPoseForGridMapVisualization (const mrpt::graphs::TNodeID nodeID) const |
return the 3D Pose of a LaserScan that is to be visualized. More... | |
virtual void | setObjectPropsFromNodeID (const mrpt::graphs::TNodeID nodeID, mrpt::opengl::CSetOfObjects::Ptr &viz_object) |
Set the properties of the map visual object based on the nodeID that it was produced by. More... | |
void | initMapVisualization () |
void | updateMapVisualization (const std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > &nodes_to_laser_scans2D, bool full_update=false) |
Update the map visualization based on the current graphSLAM state. More... | |
void | updateGTVisualization () |
Display the next ground truth position in the visualization window. More... | |
void | updateOdometryVisualization () |
Update odometry-only cloud with latest odometry estimation. More... | |
void | updateEstimatedTrajectoryVisualization (bool full_update=false) |
Update the Esstimated robot trajectory with the latest estimated robot position. More... | |
void | updateSlamMetricVisualization () |
Update the displayPlots window with the new information with regards to the metric. More... | |
Toggling of Visuals | |
Methods used for toggling various visualization features relevant to the application at hand. | |
void | toggleOdometryVisualization () |
void | toggleGTVisualization () |
void | toggleMapVisualization () |
void | toggleEstimatedTrajectoryVisualization () |
Static Protected Member Functions | |
static mrpt::system::TTimeStamp | getTimeStamp (const mrpt::obs::CActionCollection::Ptr action, const mrpt::obs::CSensoryFrame::Ptr observations, const mrpt::obs::CObservation::Ptr observation) |
Fill the TTimestamp in a consistent manner. More... | |
Class specific supplementary functions. | |
static double | accumulateAngleDiffs (const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2) |
static double | accumulateAngleDiffs (const mrpt::poses::CPose3D &p1, const mrpt::poses::CPose3D &p2) |
Protected Attributes | |
mrpt::system::CTimeLogger | m_time_logger |
Time logger instance. More... | |
GRAPH_T | m_graph |
The graph object to be built and optimized. More... | |
const bool | m_enable_visuals |
Determine if we are to enable visualization support or not. More... | |
std::string | m_config_fname |
std::string | m_rawlog_fname |
Rawlog file from which to read the measurements. More... | |
std::string | m_fname_GT |
size_t | m_GT_poses_index |
Counter for reading back the GT_poses. More... | |
size_t | m_GT_poses_step |
Rate at which to read the GT poses. More... | |
bool | m_user_decides_about_output_dir |
bool | m_has_read_config |
bool | m_observation_only_dataset |
fstreams_out | m_out_streams |
keeps track of the out fstreams so that they can be closed (if still open) in the class Dtor. More... | |
bool | m_is_paused |
Indicated if program is temporarily paused by the user. More... | |
const std::string | m_paused_message |
Message to be displayed while paused. More... | |
mrpt::graphslam::detail::CEdgeCounter | m_edge_counter |
Instance to keep track of all the edges + visualization related operations. More... | |
bool | m_use_GT |
Flag for specifying if we are going to use ground truth data at all. More... | |
std::vector< pose_t > | m_odometry_poses |
std::vector< pose_t > | m_GT_poses |
std::string | m_GT_file_format |
nodes_to_scans2D_t | m_nodes_to_laser_scans2D |
Map of NodeIDs to their corresponding LaserScans. More... | |
mrpt::obs::CObservation2DRangeScan::Ptr | m_last_laser_scan2D |
Last laser scan that the current class instance received. More... | |
mrpt::obs::CObservation2DRangeScan::Ptr | m_first_laser_scan2D |
First recorded laser scan - assigned to the root. More... | |
mrpt::obs::CObservation3DRangeScan::Ptr | m_last_laser_scan3D |
Last laser scan that the current class instance received. More... | |
mrpt::math::CMatrixDouble33 | m_rot_TUM_to_MRPT |
size_t | m_robot_model_size |
How big are the robots going to be in the scene. More... | |
mrpt::graphs::TNodeID | m_nodeID_max |
Internal counter for querying for the number of nodeIDs. More... | |
std::mutex | m_graph_section |
Mark graph modification/accessing explicitly for multithreaded implementation. More... | |
std::string | m_img_external_storage_dir |
std::string | m_img_prev_path_base |
struct mrpt::graphslam::CGraphSlamEngine::TRGBDInfoFileParams | m_info_params |
double | m_dataset_grab_time |
Time it took to record the dataset. More... | |
mrpt::system::TTimeStamp | m_init_timestamp |
First recorded timestamp in the dataset. More... | |
mrpt::system::TTimeStamp | m_curr_timestamp |
Current dataset timestamp. More... | |
pose_t | m_curr_odometry_only_pose |
Current robot position based solely on odometry. More... | |
bool | m_request_to_exit |
Indicate whether the user wants to exit the application (e.g. More... | |
std::string | m_class_name |
bool | m_is_first_time_node_reg |
Track the first node registration occurance. More... | |
std::vector< std::string > | m_supported_constraint_types |
MRPT CNetworkOfPoses constraint classes that are currently supported. More... | |
std::string | m_current_constraint_type |
Type of constraint currently in use. More... | |
VerbosityLevel | m_min_verbosity_level |
Provided messages with VerbosityLevel smaller than this value shall be ignored. More... | |
Decider/Optimizer instances. Delegating the GRAPH_T tasks to these | |
classes makes up for a modular and configurable design | |
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > * | m_node_reg |
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > * | m_edge_reg |
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > * | m_optimizer |
Visualization - related objects | |
mrpt::graphslam::CWindowManager * | m_win_manager |
mrpt::gui::CDisplayWindow3D * | m_win |
mrpt::graphslam::CWindowObserver * | m_win_observer |
mrpt::gui::CDisplayWindowPlots * | m_win_plot |
DisplayPlots instance for visualizing the evolution of the SLAM metric. More... | |
Visualization - related flags | |
Flags for visualizing various trajectories/objects of interest. These are set from the .ini configuration file. The actual visualization of these objects can be overriden if the user issues the corresponding keystrokes in the CDisplayWindow3D. In order for them to have any effect, a pointer to CDisplayWindow3D has to be given first. | |
bool | m_visualize_odometry_poses |
bool | m_visualize_GT |
bool | m_visualize_map |
bool | m_visualize_estimated_trajectory |
bool | m_visualize_SLAM_metric |
bool | m_enable_curr_pos_viewport |
bool | m_enable_intensity_viewport |
bool | m_enable_range_viewport |
textMessage - related Parameters | |
Parameters relevant to the textMessages appearing in the visualization window. These are divided into
| |
double | m_offset_x_left |
Offset from the left side of the canvas. More... | |
double | m_offset_y_odometry |
double | m_offset_y_GT |
double | m_offset_y_estimated_traj |
double | m_offset_y_timestamp |
double | m_offset_y_current_constraint_type |
double | m_offset_y_paused_message |
int | m_text_index_odometry |
int | m_text_index_GT |
int | m_text_index_estimated_traj |
int | m_text_index_timestamp |
int | m_text_index_current_constraint_type |
int | m_text_index_paused_message |
User available keystrokes | |
Keystrokes for toggling the corresponding objects in the CDisplayWindow upon user press | |
std::string | m_keystroke_pause_exec |
std::string | m_keystroke_odometry |
std::string | m_keystroke_GT |
std::string | m_keystroke_estimated_trajectory |
std::string | m_keystroke_map |
Trajectories colors | |
mrpt::img::TColor | m_odometry_color |
mrpt::img::TColor | m_GT_color |
mrpt::img::TColor | m_estimated_traj_color |
mrpt::img::TColor | m_optimized_map_color |
mrpt::img::TColor | m_current_constraint_type_color |
Slam Metric related variables | |
std::map< mrpt::graphs::TNodeID, size_t > | m_nodeID_to_gt_indices |
Map from nodeIDs to their corresponding closest GT pose index. More... | |
double | m_curr_deformation_energy |
std::vector< double > | m_deformation_energy_vec |
Map-related objects | |
Cached version and corresponding flag of map | |
mrpt::maps::COccupancyGridMap2D::Ptr | m_gridmap_cached |
mrpt::maps::CSimpleMap | m_simple_map_cached |
Acquired map in CSimpleMap representation. More... | |
mrpt::maps::COctoMap::Ptr | m_octomap_cached |
bool | m_map_is_cached |
Indicates if the map is cached. More... | |
mrpt::system::TTimeStamp | m_map_acq_time |
Timestamp at which the map was computed. More... | |
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') |
Private Member Functions | |
std::string | generateStringFromFormat (const char *fmt, va_list argp) const |
Helper method for generating a std::string instance from printf-like arguments. More... | |
Private Attributes | |
std::string | m_logger_name |
std::deque< TMsg > | m_history |
std::deque< output_logger_callback_t > | m_listCallbacks |
Logging methods | |
void | logStr (const VerbosityLevel level, const std::string &msg_str) const |
Main method to add the specified message string to the logger. More... | |
void | logFmt (const VerbosityLevel level, const char *fmt,...) const MRPT_printf_format_check(3 |
Alternative logging method, which mimics the printf behavior. More... | |
void void | logCond (const VerbosityLevel level, bool cond, const std::string &msg_str) const |
Log the given message only if the condition is satisfied. More... | |
void | setLoggerName (const std::string &name) |
Set the name of the COutputLogger instance. More... | |
std::string | getLoggerName () const |
Return the name of the COutputLogger instance. More... | |
void | setMinLoggingLevel (const VerbosityLevel level) |
Set the minimum logging level for which the incoming logs are going to be taken into account. More... | |
void | setVerbosityLevel (const VerbosityLevel level) |
alias of setMinLoggingLevel() More... | |
VerbosityLevel | getMinLoggingLevel () const |
bool | isLoggingLevelVisible (VerbosityLevel level) const |
void | getLogAsString (std::string &log_contents) const |
Fill the provided string with the contents of the logger's history in std::string representation. More... | |
std::string | getLogAsString () const |
Get the history of COutputLogger instance in a string representation. More... | |
void | writeLogToFile (const std::string *fname_in=NULL) const |
Write the contents of the COutputLogger instance to an external file. More... | |
void | dumpLogToConsole () const |
Dump the current contents of the COutputLogger instance in the terminal window. More... | |
std::string | getLoggerLastMsg () const |
Return the last Tmsg instance registered in the logger history. More... | |
void | getLoggerLastMsg (std::string &msg_str) const |
Fill inputtted string with the contents of the last message in history. More... | |
void | loggerReset () |
Reset the contents of the logger instance. More... | |
void | logRegisterCallback (output_logger_callback_t userFunc) |
bool | logDeregisterCallback (output_logger_callback_t userFunc) |
bool | logging_enable_console_output |
[Default=true] Set it to false in case you don't want the logged messages to be dumped to the output automatically. More... | |
bool | logging_enable_keep_record |
[Default=false] Enables storing all messages into an internal list. More... | |
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::constraint_t = typename GRAPH_T::constraint_t |
Type of graph constraints.
Definition at line 165 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::fstreams_out = std::map<std::string, mrpt::io::CFileOutputStream> |
Handy typedefs.
Map for managing output file streams.
Definition at line 160 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::fstreams_out_it = typename fstreams_out::iterator |
Map for iterating over output file streams.
Definition at line 162 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::global_pose_t = typename GRAPH_T::global_pose_t |
Definition at line 168 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::nodes_to_scans2D_t = std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr> |
Definition at line 170 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pose_t = typename GRAPH_T::constraint_t::type_value |
Type of underlying poses (2D/3D).
Definition at line 167 of file CGraphSlamEngine.h.
mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::CGraphSlamEngine | ( | const std::string & | config_file, |
const std::string & | rawlog_fname = "" , |
||
const std::string & | fname_GT = "" , |
||
mrpt::graphslam::CWindowManager * | win_manager = NULL , |
||
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > * | node_reg = NULL , |
||
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > * | edge_reg = NULL , |
||
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > * | optimizer = NULL |
||
) |
Constructor of CGraphSlamEngine class template.
// TODO - remove the deprecated arguments
[in] | config_file | .ini file containing the configuration parameters for the CGraphSlamEngine as well as the deciders/optimizer classes that CGraphSlamEngine is using |
[in] | win_manager | CwindowManager instance that includes a pointer to a CDisplayWindow3D and a CWindowObserver instance for properly interacting with the display window |
[in] | rawlog_fname | .rawlog dataset file, containing the robot measurements. CGraphSlamEngine supports both MRPT rwalog formats but in order for graphSLAM to work as expected the rawlog foromat has to be supported by the every decider/optimizer class that CGraphSlamEngine makes use of. |
[in] | fname_GT | Textfile containing the ground truth path of the robot. Currently the class can read ground truth files corresponding either to RGBD - TUM datasets or to rawlog files generated with the GridMapNavSimul MRPT application. // TODO add the deciders/optimizer |
Definition at line 35 of file CGraphSlamEngine_impl.h.
|
virtual |
Default Destructor.
Definition at line 70 of file CGraphSlamEngine_impl.h.
|
virtual |
Main class method responsible for parsing each measurement and for executing graphSLAM.
Definition at line 526 of file CGraphSlamEngine_impl.h.
|
staticprotected |
Definition at line 2559 of file CGraphSlamEngine_impl.h.
|
staticprotected |
Definition at line 2565 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1569 of file CGraphSlamEngine_impl.h.
|
inline |
Compute the map of the environment based on the recorded measurements.
Definition at line 973 of file CGraphSlamEngine_impl.h.
|
protected |
Compare the SLAM result (estimated trajectory) with the GT path.
See A Comparison of SLAM Algorithms Based on a Graph of Relations for more details on this.
Definition at line 2482 of file CGraphSlamEngine_impl.h.
|
protected |
Cut down on the size of the given laser scan.
Handy for reducing the size of the resulting mrpt::opengl::CSetOfObjects that would be inserted in the visualization scene. Increase the decimation rate - keep-every_n_entries - to reduce the computational cost of updating the map visualization
Definition at line 2012 of file CGraphSlamEngine_impl.h.
|
inherited |
Dump the current contents of the COutputLogger instance in the terminal window.
Definition at line 179 of file COutputLogger.cpp.
|
protected |
Wrapper method that used for printing error messages in a consistent manner.
Makes use of the COutputLogger instance. Prints error message when toggling illegal visual features in the display window
Definition at line 1791 of file CGraphSlamEngine_impl.h.
|
protected |
Wrapper around the GRAPH_T::dijkstra_nodes_estimate.
Update the global position of the nodes
Definition at line 875 of file CGraphSlamEngine_impl.h.
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::execGraphSlamStep | ( | mrpt::obs::CObservation::Ptr & | observation, |
size_t & | rawlog_entry | ||
) |
Wrapper method around _execGraphSlamStep.
Handy for not having to specify any action/observations objects
Definition at line 513 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::generateReportFiles | ( | const std::string & | output_dir_fname_in | ) |
Generate and write to a corresponding report for each of the respective self/decider/optimizer classes.
[in] | output_dir_fname | directory name to generate the files in. Directory must be crated prior to this call |
Definition at line 2728 of file CGraphSlamEngine_impl.h.
|
privateinherited |
Helper method for generating a std::string instance from printf-like arguments.
Definition at line 99 of file COutputLogger.cpp.
References mrpt::system::os::vsnprintf().
GRAPH_T::global_pose_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getCurrentRobotPosEstimation |
Query CGraphSlamEngine instance for the current estimated robot position.
Definition at line 98 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getDeformationEnergyVector | ( | std::vector< double > * | vec_out | ) | const |
Fill the given vector with the deformation energy values computed for the SLAM evaluation metric.
[out] | vec_out | deformation energy vector to be filled |
Definition at line 2833 of file CGraphSlamEngine_impl.h.
|
protected |
Fill the provided string with a detailed report of the class state.
Report includes the following:
Definition at line 2638 of file CGraphSlamEngine_impl.h.
|
inline |
Return a reference to the underlying GRAPH_T instance.
Definition at line 327 of file CGraphSlamEngine.h.
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getGraphSlamStats | ( | std::map< std::string, int > * | node_stats, |
std::map< std::string, int > * | edge_stats, | ||
mrpt::system::TTimeStamp * | timestamp = NULL |
||
) |
Fill the given maps with stats regarding the overall execution of graphslam.
Definition at line 2687 of file CGraphSlamEngine_impl.h.
|
inherited |
Get the history of COutputLogger instance in a string representation.
Definition at line 148 of file COutputLogger.cpp.
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport().
|
inherited |
Fill the provided string with the contents of the logger's history in std::string representation.
Definition at line 143 of file COutputLogger.cpp.
|
inherited |
Return the last Tmsg instance registered in the logger history.
Definition at line 184 of file COutputLogger.cpp.
References mrpt::system::COutputLogger::TMsg::getAsString().
|
inherited |
Fill inputtted string with the contents of the last message in history.
Definition at line 190 of file COutputLogger.cpp.
|
inherited |
Return the name of the COutputLogger instance.
Definition at line 132 of file COutputLogger.cpp.
Referenced by mrpt::system::COutputLogger::TMsg::TMsg().
|
protectedvirtual |
return the 3D Pose of a LaserScan that is to be visualized.
Used during the computeMap call for the occupancy gridmap
Definition at line 1851 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap | ( | mrpt::maps::COccupancyGridMap2D::Ptr | map, |
mrpt::system::TTimeStamp * | acquisition_time = NULL |
||
) | const |
Definition at line 921 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap | ( | mrpt::maps::COctoMap::Ptr | map, |
mrpt::system::TTimeStamp * | acquisition_time = NULL |
||
) | const |
Definition at line 948 of file CGraphSlamEngine_impl.h.
|
inlineinherited |
Definition at line 200 of file system/COutputLogger.h.
References mrpt::system::COutputLogger::m_min_verbosity_level.
Referenced by mrpt::maps::CRandomFieldGridMap2D::isEnabledVerbose(), and mrpt::slam::CMetricMapBuilderRBPF::processActionObservation().
|
virtual |
Return the list of nodeIDs which make up robot trajectory.
Definition at line 113 of file CGraphSlamEngine_impl.h.
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getParamsAsString |
Wrapper around getParamsAsString.
Returns the generated string instead of passing it as an argument to the call
Definition at line 1088 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getParamsAsString | ( | std::string * | params_out | ) | const |
Fill in the provided string with the class configuration parameters.
Definition at line 1099 of file CGraphSlamEngine_impl.h.
|
inline |
Return the filename of the used rawlog file.
Definition at line 329 of file CGraphSlamEngine.h.
|
virtual |
Definition at line 106 of file CGraphSlamEngine_impl.h.
|
staticprotected |
Fill the TTimestamp in a consistent manner.
Method can be used in both MRPT Rawlog formats
[in] | action_ptr | Pointer to the action (action-observations format) |
[in] | observations | Pointer to list of observations (action-observations format) |
[in] | observation | Pointer to single observation (observation-only format) |
Definition at line 1806 of file CGraphSlamEngine_impl.h.
|
protected |
General initialization method to call from the Class Constructors.
Definition at line 121 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1337 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 2203 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 2042 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1266 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1858 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 2128 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1199 of file CGraphSlamEngine_impl.h.
|
protected |
Automate the creation and initialization of a results file relevant to the application.
Open the file (corresponding to the provided filename) and write an introductory message.
Definition at line 1161 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1313 of file CGraphSlamEngine_impl.h.
|
protected |
Method to help overcome the partial template specialization restriction of C++.
Apply polymorphism by overloading function arguments instead
Definition at line 1321 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1330 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 2579 of file CGraphSlamEngine_impl.h.
|
protected |
|
inlineinherited |
Definition at line 201 of file system/COutputLogger.h.
References mrpt::system::COutputLogger::m_min_verbosity_level.
Referenced by mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), and mrpt::system::COutputLoggerStreamWrapper::~COutputLoggerStreamWrapper().
|
inline |
Definition at line 409 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::resumeExec(), and mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::togglePause().
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::loadParams | ( | const std::string & | fname | ) |
Read the configuration variables from the .ini file specified by the user.
Method is automatically called, upon CGraphSlamEngine initialization
Definition at line 1027 of file CGraphSlamEngine_impl.h.
|
inherited |
Log the given message only if the condition is satisfied.
Definition at line 120 of file COutputLogger.cpp.
|
inherited |
Definition at line 287 of file COutputLogger.cpp.
References getAddress().
|
inherited |
Alternative logging method, which mimics the printf behavior.
Handy for not having to first use mrpt::format to pass a std::string message to logStr
Definition at line 80 of file COutputLogger.cpp.
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::CICPCriteriaNRD(), mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), CGraphSlamHandler< GRAPH_T >::execute(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), CGraphSlamHandler< GRAPH_T >::initOutputDir(), CGraphSlamHandler< GRAPH_T >::initVisualization(), mrpt::nav::CNavigatorManualSequence::navigationStep(), mrpt::nav::CAbstractNavigator::performNavigationStepNavigating(), CGraphSlamHandler< GRAPH_T >::readConfigFname(), CGraphSlamHandler< GRAPH_T >::saveResults(), CGraphSlamHandler< GRAPH_T >::setResultsDirName(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), and CGraphSlamHandler< GRAPH_T >::~CGraphSlamHandler().
|
inherited |
Reset the contents of the logger instance.
Called upon construction.
Definition at line 195 of file COutputLogger.cpp.
References mrpt::system::LVL_INFO.
|
inherited |
Definition at line 274 of file COutputLogger.cpp.
|
inherited |
Main method to add the specified message string to the logger.
Definition at line 61 of file COutputLogger.cpp.
References mrpt::system::COutputLogger::TMsg::body, mrpt::system::COutputLogger::TMsg::dumpToConsole(), mrpt::system::COutputLogger::TMsg::level, mrpt::system::COutputLogger::TMsg::name, and mrpt::system::COutputLogger::TMsg::timestamp.
Referenced by mrpt::slam::PF_implementation< mrpt::math::TPose3D, CMonteCarloLocalization3D, mrpt::bayes::particle_storage_mode::VALUE >::PF_SLAM_implementation_pfAuxiliaryPFStandardAndOptimal(), mrpt::nav::CReactiveNavigationSystem::STEP1_InitPTGs(), and mrpt::system::COutputLoggerStreamWrapper::~COutputLoggerStreamWrapper().
|
protectedvirtual |
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception.
\raise logic_error if the expected node count mismatches with the graph current node count.
Definition at line 886 of file CGraphSlamEngine_impl.h.
|
inline |
Definition at line 438 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::togglePause().
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::printParams |
Print the problem parameters to the console for verification.
Method is a wrapper around CGraphSlamEngine::getParamsAsString method
Definition at line 1148 of file CGraphSlamEngine_impl.h.
|
inlineprotected |
Query the observer instance for any user events.
Query the given observer for any events (keystrokes, mouse clicks, that may have occurred in the CDisplayWindow3D and fill in the corresponding class variables
Definition at line 1617 of file CGraphSlamEngine_impl.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec().
|
static |
Parse the ground truth .txt file and fill in the corresponding gt_poses vector.
It is assumed that the rawlog, thererfore the groundtruth file has been generated using the GridMapNavSimul MRPT application. If not user should abide the ground-truth file format to that of the files generated by the GridMapNavSimul app.
[in] | fname_GT | Ground truth filename from which the measurements are to be read |
[out] | gt_poses | std::vector which is to contain the 2D ground truth poses. |
[out] | gt_timestamps | std::vector which is to contain the timestamps for the corresponding ground truth poses. Ignore this argument if timestamps are not needed. |
Definition at line 1389 of file CGraphSlamEngine_impl.h.
|
static |
Definition at line 1446 of file CGraphSlamEngine_impl.h.
|
static |
Parse the ground truth .txt file and fill in the corresponding m_GT_poses vector.
The poses returned are given with regards to the MRPT reference frame.
It is assumed that the groundtruth file has been generated using the rgbd_dataset2rawlog MRPT tool.
[in] | fname_GT | Ground truth filename from which the measurements are to be read |
[out] | gt_poses | std::vector which is to contain the 2D ground truth poses. |
[out] | gt_timestamps | std::vector which is to contain the timestamps for the corresponding ground truth poses. Ignore this argument if timestamps are not needed. |
Definition at line 1454 of file CGraphSlamEngine_impl.h.
|
inline |
Definition at line 421 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::togglePause().
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::save3DScene | ( | const std::string * | fname_in = nullptr | ) | const |
Wrapper method around the COpenGLScene::saveToFile method.
[in] | Name | of the generated graph file - Defaults to "output_graph" if not set by the user |
Definition at line 2430 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::saveGraph | ( | const std::string * | fname_in = nullptr | ) | const |
Wrapper method around the GRAPH_T::saveToTextFile method.
Method saves the graph in the format used by TORO & HoG-man strategies
[in] | fname_in | Name of the generated graph file - Defaults to "output_graph" if not set by the user |
Definition at line 2406 of file CGraphSlamEngine_impl.h.
|
protected |
Set the opengl model that indicates the latest position of the trajectory at hand.
[in] | model_name | Name of the resulting opengl object. |
[in] | model_color | Color of the object. |
[in] | model_size | Scaling of the object. |
[in] | init_pose | Initial position of the object. |
Definition at line 2813 of file CGraphSlamEngine_impl.h.
|
inherited |
Set the name of the COutputLogger instance.
Definition at line 127 of file COutputLogger.cpp.
Referenced by mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::slam::CMonteCarloLocalization2D::CMonteCarloLocalization2D(), mrpt::slam::CMonteCarloLocalization3D::CMonteCarloLocalization3D(), and mrpt::graphslam::CWindowManager::initCWindowManager().
|
inherited |
Set the minimum logging level for which the incoming logs are going to be taken into account.
String messages with specified VerbosityLevel smaller than the min, will not be outputted to the screen and neither will a record of them be stored in by the COutputLogger instance
Definition at line 133 of file COutputLogger.cpp.
Referenced by mrpt::maps::CRandomFieldGridMap2D::enableVerbose(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), mrpt::hwdrivers::CHokuyoURG::initialize(), and mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().
|
protectedvirtual |
Set the properties of the map visual object based on the nodeID that it was produced by.
Derived classes may override this method if they want to have different visual properties (color, shape etc.) for different nodeIDs.
Definition at line 2002 of file CGraphSlamEngine_impl.h.
|
inherited |
alias of setMinLoggingLevel()
Definition at line 138 of file COutputLogger.cpp.
Referenced by mrpt::nav::CAbstractNavigator::CAbstractNavigator(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::comms::CServerTCPSocket::CServerTCPSocket(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), and mrpt::math::ransac_detect_2D_lines().
|
protected |
Definition at line 1763 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1694 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1722 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 1666 of file CGraphSlamEngine_impl.h.
|
inline |
Definition at line 410 of file CGraphSlamEngine.h.
|
protected |
Wrapper around the deciders/optimizer updateVisuals methods.
Definition at line 1220 of file CGraphSlamEngine_impl.h.
|
inlineprotectedvirtual |
Update the viewport responsible for displaying the graph-building procedure in the estimated position of the robot.
Definition at line 1366 of file CGraphSlamEngine_impl.h.
|
protected |
Update the Esstimated robot trajectory with the latest estimated robot position.
Update CSetOfLines visualization object with the latest graph node position. If full update is asked, method clears the CSetOfLines object and redraws all the lines based on the updated (optimized) positions of the nodes
Definition at line 2253 of file CGraphSlamEngine_impl.h.
|
protected |
Display the next ground truth position in the visualization window.
Definition at line 2091 of file CGraphSlamEngine_impl.h.
|
protected |
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport.
Definition at line 1286 of file CGraphSlamEngine_impl.h.
|
protected |
Update the map visualization based on the current graphSLAM state.
Map is produced by arranging the range scans based on the estimated robot trajectory.
Definition at line 1871 of file CGraphSlamEngine_impl.h.
|
protected |
Update odometry-only cloud with latest odometry estimation.
Definition at line 2170 of file CGraphSlamEngine_impl.h.
|
protected |
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport.
Definition at line 1235 of file CGraphSlamEngine_impl.h.
|
protected |
Update the displayPlots window with the new information with regards to the metric.
Definition at line 2603 of file CGraphSlamEngine_impl.h.
|
inherited |
Write the contents of the COutputLogger instance to an external file.
Upon call to this method, COutputLogger dumps the contents of all the logged commands so far to the specified external file. By default the filename is set to ${LOGGERNAME}.log except if the fname parameter is provided
Definition at line 154 of file COutputLogger.cpp.
References ASSERTMSG_, and mrpt::format().
|
staticprotected |
Separator string to be used in debugging messages.
Definition at line 995 of file CGraphSlamEngine.h.
|
inherited |
[Default=true] Set it to false in case you don't want the logged messages to be dumped to the output automatically.
Definition at line 239 of file system/COutputLogger.h.
|
inherited |
[Default=false] Enables storing all messages into an internal list.
Definition at line 242 of file system/COutputLogger.h.
|
staticinherited |
Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor.
Implementation file for the COutputLogger header class.
Handy for coloring the input based on the verbosity of the message
Definition at line 124 of file system/COutputLogger.h.
Referenced by mrpt::system::COutputLogger::TMsg::dumpToConsole().
|
staticinherited |
Map from VerbosityLevels to their corresponding names.
Handy for printing the current message VerbosityLevel along with the actual content
Definition at line 129 of file system/COutputLogger.h.
Referenced by mrpt::system::COutputLogger::TMsg::getAsString().
|
protected |
Definition at line 978 of file CGraphSlamEngine.h.
|
protected |
Definition at line 739 of file CGraphSlamEngine.h.
|
protected |
Definition at line 909 of file CGraphSlamEngine.h.
|
protected |
Current robot position based solely on odometry.
Definition at line 951 of file CGraphSlamEngine.h.
|
protected |
Current dataset timestamp.
Definition at line 949 of file CGraphSlamEngine.h.
|
protected |
Type of constraint currently in use.
Definition at line 991 of file CGraphSlamEngine.h.
|
protected |
Definition at line 878 of file CGraphSlamEngine.h.
|
protected |
Time it took to record the dataset.
Processing time should (at least) be equal to the grab time for the algorithm to run in real-time
Definition at line 944 of file CGraphSlamEngine.h.
|
protected |
Definition at line 910 of file CGraphSlamEngine.h.
|
protected |
Instance to keep track of all the edges + visualization related operations.
Definition at line 844 of file CGraphSlamEngine.h.
|
protected |
Definition at line 732 of file CGraphSlamEngine.h.
|
protected |
Definition at line 789 of file CGraphSlamEngine.h.
|
protected |
Definition at line 790 of file CGraphSlamEngine.h.
|
protected |
Definition at line 791 of file CGraphSlamEngine.h.
|
protected |
Determine if we are to enable visualization support or not.
Definition at line 737 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::resumeExec().
|
protected |
Definition at line 876 of file CGraphSlamEngine.h.
|
protected |
First recorded laser scan - assigned to the root.
Definition at line 867 of file CGraphSlamEngine.h.
|
protected |
Definition at line 747 of file CGraphSlamEngine.h.
|
protected |
The graph object to be built and optimized.
Definition at line 725 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::getGraph().
|
mutableprotected |
Mark graph modification/accessing explicitly for multithreaded implementation.
Definition at line 895 of file CGraphSlamEngine.h.
|
mutableprotected |
Definition at line 962 of file CGraphSlamEngine.h.
|
protected |
Definition at line 875 of file CGraphSlamEngine.h.
|
protected |
Definition at line 858 of file CGraphSlamEngine.h.
|
protected |
Definition at line 856 of file CGraphSlamEngine.h.
|
protected |
Counter for reading back the GT_poses.
Definition at line 750 of file CGraphSlamEngine.h.
|
protected |
Rate at which to read the GT poses.
Definition at line 752 of file CGraphSlamEngine.h.
|
protected |
Definition at line 756 of file CGraphSlamEngine.h.
|
mutableprivateinherited |
Definition at line 312 of file system/COutputLogger.h.
|
protected |
Definition at line 899 of file CGraphSlamEngine.h.
|
protected |
Definition at line 900 of file CGraphSlamEngine.h.
|
protected |
|
protected |
First recorded timestamp in the dataset.
Definition at line 947 of file CGraphSlamEngine.h.
|
protected |
Track the first node registration occurance.
Handy so that we can assign a measurement to the root node as well.
Definition at line 983 of file CGraphSlamEngine.h.
|
mutableprotected |
Indicated if program is temporarily paused by the user.
Definition at line 796 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::isPaused(), mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::resumeExec().
|
protected |
Definition at line 837 of file CGraphSlamEngine.h.
|
protected |
Definition at line 836 of file CGraphSlamEngine.h.
|
protected |
Definition at line 838 of file CGraphSlamEngine.h.
|
protected |
Definition at line 835 of file CGraphSlamEngine.h.
|
protected |
Definition at line 834 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec().
|
protected |
Last laser scan that the current class instance received.
Definition at line 865 of file CGraphSlamEngine.h.
|
protected |
Last laser scan that the current class instance received.
Definition at line 870 of file CGraphSlamEngine.h.
|
privateinherited |
Definition at line 314 of file system/COutputLogger.h.
|
privateinherited |
Definition at line 310 of file system/COutputLogger.h.
|
mutableprotected |
Timestamp at which the map was computed.
Definition at line 975 of file CGraphSlamEngine.h.
|
mutableprotected |
Indicates if the map is cached.
Definition at line 970 of file CGraphSlamEngine.h.
|
protectedinherited |
Provided messages with VerbosityLevel smaller than this value shall be ignored.
Definition at line 252 of file system/COutputLogger.h.
Referenced by mrpt::system::COutputLogger::getMinLoggingLevel(), and mrpt::system::COutputLogger::isLoggingLevelVisible().
|
protected |
Definition at line 731 of file CGraphSlamEngine.h.
|
protected |
Internal counter for querying for the number of nodeIDs.
Handy for not locking the m_graph resource
Definition at line 891 of file CGraphSlamEngine.h.
|
protected |
Map from nodeIDs to their corresponding closest GT pose index.
Keep track of the nodeIDs instead of the node positions as the latter are about to change in the Edge Registration / Loop closing procedures
Definition at line 908 of file CGraphSlamEngine.h.
|
protected |
Map of NodeIDs to their corresponding LaserScans.
Definition at line 862 of file CGraphSlamEngine.h.
|
protected |
Definition at line 757 of file CGraphSlamEngine.h.
|
mutableprotected |
Definition at line 965 of file CGraphSlamEngine.h.
|
protected |
Definition at line 874 of file CGraphSlamEngine.h.
|
protected |
Definition at line 855 of file CGraphSlamEngine.h.
|
protected |
Offset from the left side of the canvas.
Common for all the messages that are displayed on that side.
Definition at line 812 of file CGraphSlamEngine.h.
|
protected |
Definition at line 818 of file CGraphSlamEngine.h.
|
protected |
Definition at line 816 of file CGraphSlamEngine.h.
|
protected |
Definition at line 815 of file CGraphSlamEngine.h.
|
protected |
Definition at line 814 of file CGraphSlamEngine.h.
|
protected |
Definition at line 819 of file CGraphSlamEngine.h.
|
protected |
Definition at line 817 of file CGraphSlamEngine.h.
|
protected |
Definition at line 877 of file CGraphSlamEngine.h.
|
protected |
Definition at line 733 of file CGraphSlamEngine.h.
|
protected |
keeps track of the out fstreams so that they can be closed (if still open) in the class Dtor.
Definition at line 762 of file CGraphSlamEngine.h.
|
protected |
Message to be displayed while paused.
Definition at line 799 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec().
|
protected |
Rawlog file from which to read the measurements.
If string is empty, process is to be run online
Definition at line 745 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::getRawlogFname().
|
protected |
Indicate whether the user wants to exit the application (e.g.
pressed by pressign ctrl-c)
Definition at line 956 of file CGraphSlamEngine.h.
|
protected |
How big are the robots going to be in the scene.
Definition at line 886 of file CGraphSlamEngine.h.
|
protected |
Definition at line 884 of file CGraphSlamEngine.h.
|
mutableprotected |
Acquired map in CSimpleMap representation.
Definition at line 964 of file CGraphSlamEngine.h.
|
protected |
MRPT CNetworkOfPoses constraint classes that are currently supported.
Definition at line 988 of file CGraphSlamEngine.h.
|
protected |
Definition at line 825 of file CGraphSlamEngine.h.
|
protected |
Definition at line 823 of file CGraphSlamEngine.h.
|
protected |
Definition at line 822 of file CGraphSlamEngine.h.
|
protected |
Definition at line 821 of file CGraphSlamEngine.h.
|
protected |
Definition at line 826 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::resumeExec().
|
protected |
Definition at line 824 of file CGraphSlamEngine.h.
|
protected |
Time logger instance.
Definition at line 722 of file CGraphSlamEngine.h.
|
protected |
Flag for specifying if we are going to use ground truth data at all.
This is set to true either if the evolution of the SLAM metric or the ground truth visualization is set to true.
Definition at line 852 of file CGraphSlamEngine.h.
|
protected |
Definition at line 754 of file CGraphSlamEngine.h.
|
protected |
Definition at line 787 of file CGraphSlamEngine.h.
|
protected |
Definition at line 785 of file CGraphSlamEngine.h.
|
protected |
Definition at line 786 of file CGraphSlamEngine.h.
|
protected |
Definition at line 784 of file CGraphSlamEngine.h.
|
protected |
Definition at line 788 of file CGraphSlamEngine.h.
|
protected |
Definition at line 767 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< mrpt::graphs::CNetworkOfPoses2DInf >::resumeExec().
|
protected |
Definition at line 766 of file CGraphSlamEngine.h.
|
protected |
Definition at line 768 of file CGraphSlamEngine.h.
|
protected |
DisplayPlots instance for visualizing the evolution of the SLAM metric.
Definition at line 772 of file CGraphSlamEngine.h.
|
staticprotected |
Definition at line 996 of file CGraphSlamEngine.h.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST |