Main MRPT website > C++ reference for MRPT 1.5.6
List of all members | Classes | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Static Protected Attributes
mrpt::graphslam::CGraphSlamEngine< GRAPH_T > Class Template Reference

Detailed Description

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
class mrpt::graphslam::CGraphSlamEngine< GRAPH_T >

Main file for the GraphSlamEngine.

Description

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:

Note
The GRAPH_T resource is accessed after having locked the relevant section m_graph_section. Critical section is also locked prior to the calls to the deciders/optimizers .

.ini Configuration Parameters

The configuration parameters of the current decider class are listed below. These parameters are parsed from an external .ini configuration file from their respective section. If an optional parameter is not found a default value is used instead. If a mandatory/required parameter is not found a runtime error is raised. For a sample configuration file see $mrpt/share/mrpt/config_files/graphslam-engine/laser_odometry.ini (Modify $mrpt according to the path of your mrpt source directory).
Note
Implementation can be found in the file CGraphSlamEngine_impl.h

Definition at line 191 of file CGraphSlamEngine.h.

#include <mrpt/graphslam/CGraphSlamEngine.h>

Inheritance diagram for mrpt::graphslam::CGraphSlamEngine< GRAPH_T >:
Inheritance graph

Classes

struct  TRGBDInfoFileParams
 Struct responsible for keeping the parameters of the .info file in RGBD related datasets. More...
 

Public Types

typedef std::map< std::string, mrpt::utils::CFileOutputStream * > fstreams_out
 Handy typedefs. More...
 
typedef std::map< std::string, mrpt::utils::CFileOutputStream * >::iterator fstreams_out_it
 Map for iterating over output file streams. More...
 
typedef GRAPH_T::constraint_t constraint_t
 Type of graph constraints. More...
 
typedef GRAPH_T::constraint_t::type_value pose_t
 Type of underlying poses (2D/3D). More...
 
typedef GRAPH_T::global_pose_t global_pose_t
 
typedef std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > nodes_to_scans2D_t
 

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 void getRobotEstimatedTrajectory (typename GRAPH_T::global_poses_t *graph_poses) const
 
virtual void getNodeIDsOfEstimatedTrajectory (std::set< mrpt::utils::TNodeID > *nodes_set) const
 Return the list of nodeIDs which make up robot trajectory. More...
 
void saveGraph (const std::string *fname_in=NULL) const
 Wrapper method around the GRAPH_T::saveToTextFile method. More...
 
void save3DScene (const std::string *fname_in=NULL) 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::CObservationPtr &observation, size_t &rawlog_entry)
 Wrapper method around _execGraphSlamStep. More...
 
virtual bool _execGraphSlamStep (mrpt::obs::CActionCollectionPtr &action, mrpt::obs::CSensoryFramePtr &observations, mrpt::obs::CObservationPtr &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::COccupancyGridMap2DPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
 
void getMap (mrpt::maps::COctoMapPtr 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...
 

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::utils::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::CSetOfObjectsPtr setCurrentPositionModel (const std::string &model_name, const mrpt::utils::TColor &model_color=mrpt::utils::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::CSetOfObjectsPtr initRobotModelVisualization ()
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal (const mrpt::poses::CPose2D &p_unused)
 Method to help overcome the partial template specialization restriction of C++. More...
 
mrpt::opengl::CSetOfObjectsPtr 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::utils::TNodeID nodeID) const
 return the 3D Pose of a LaserScan that is to be visualized. More...
 
virtual void setObjectPropsFromNodeID (const mrpt::utils::TNodeID nodeID, mrpt::opengl::CSetOfObjectsPtr &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::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > &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::CActionCollectionPtr action, const mrpt::obs::CSensoryFramePtr observations, const mrpt::obs::CObservationPtr 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::utils::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_tm_odometry_poses
 
std::vector< pose_tm_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::CObservation2DRangeScanPtr m_last_laser_scan2D
 Last laser scan that the current class instance received. More...
 
mrpt::obs::CObservation2DRangeScanPtr m_first_laser_scan2D
 First recorded laser scan - assigned to the root. More...
 
mrpt::obs::CObservation3DRangeScanPtr 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::utils::TNodeID m_nodeID_max
 Internal counter for querying for the number of nodeIDs. More...
 
mrpt::synch::CCriticalSection 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::stringm_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...
 
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::CWindowManagerm_win_manager
 
mrpt::gui::CDisplayWindow3Dm_win
 
mrpt::graphslam::CWindowObserverm_win_observer
 
mrpt::gui::CDisplayWindowPlotsm_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

  • Y offsets: vertical position of the textMessage, starting from the top side.
  • Indices: Unique ID number of each textMessage, used for updating it
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::utils::TColor m_odometry_color
 
mrpt::utils::TColor m_GT_color
 
mrpt::utils::TColor m_estimated_traj_color
 
mrpt::utils::TColor m_optimized_map_color
 
mrpt::utils::TColor m_current_constraint_type_color
 
Slam Metric related variables
std::map< mrpt::utils::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::COccupancyGridMap2DPtr m_gridmap_cached
 
mrpt::maps::CSimpleMap m_simple_map_cached
 Acquired map in CSimpleMap representation. More...
 
mrpt::maps::COctoMapPtr 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')
 

Member Typedef Documentation

◆ constraint_t

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef GRAPH_T::constraint_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::constraint_t

Type of graph constraints.

Definition at line 202 of file CGraphSlamEngine.h.

◆ fstreams_out

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef std::map<std::string, mrpt::utils::CFileOutputStream*> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::fstreams_out

Handy typedefs.

Map for managing output file streams.

Definition at line 197 of file CGraphSlamEngine.h.

◆ fstreams_out_it

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef std::map<std::string, mrpt::utils::CFileOutputStream*>::iterator mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::fstreams_out_it

Map for iterating over output file streams.

Definition at line 199 of file CGraphSlamEngine.h.

◆ global_pose_t

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef GRAPH_T::global_pose_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::global_pose_t

Definition at line 205 of file CGraphSlamEngine.h.

◆ nodes_to_scans2D_t

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::nodes_to_scans2D_t

Definition at line 208 of file CGraphSlamEngine.h.

◆ pose_t

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef GRAPH_T::constraint_t::type_value mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pose_t

Type of underlying poses (2D/3D).

Definition at line 204 of file CGraphSlamEngine.h.

Constructor & Destructor Documentation

◆ CGraphSlamEngine()

template<class GRAPH_T >
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

Parameters
[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_managerCwindowManager 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_GTTextfile 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
Note
If a NULL CWindowManager pointer is porovided, the application runs on headless mode . In this case, no visual feedback is given but application receives a big boost in performance

Definition at line 24 of file CGraphSlamEngine_impl.h.

References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initClass().

◆ ~CGraphSlamEngine()

template<class GRAPH_T >
mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::~CGraphSlamEngine ( )
virtual

Default Destructor.

Definition at line 58 of file CGraphSlamEngine_impl.h.

References MRPT_LOG_DEBUG_STREAM, MRPT_LOG_INFO_STREAM, and mrpt::system::strCmpI().

Member Function Documentation

◆ _execGraphSlamStep()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::_execGraphSlamStep ( mrpt::obs::CActionCollectionPtr &  action,
mrpt::obs::CSensoryFramePtr &  observations,
mrpt::obs::CObservationPtr &  observation,
size_t &  rawlog_entry 
)
virtual

Main class method responsible for parsing each measurement and for executing graphSLAM.

Note
Method reads each measurement seperately, so the application that invokes it is responsibe for fetching the measurements (e.g. from a rawlog file).
Returns
False if the user has requested to exit the graphslam execution (e.g. pressed ctrl-c), True otherwise

Definition at line 498 of file CGraphSlamEngine_impl.h.

References ASSERT_, ASSERTMSG_, mrpt::format(), mrpt::system::getCurrentTime(), INVALID_TIMESTAMP, IS_CLASS, MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_ERROR_STREAM, MRPT_START, mrpt::system::strCmpI(), THROW_EXCEPTION, mrpt::system::timeDifference(), and mrpt::system::timeToString().

◆ accumulateAngleDiffs() [1/2]

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::accumulateAngleDiffs ( const mrpt::poses::CPose2D p1,
const mrpt::poses::CPose2D p2 
)
staticprotected

◆ accumulateAngleDiffs() [2/2]

template<class GRAPH_T >
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::accumulateAngleDiffs ( const mrpt::poses::CPose3D p1,
const mrpt::poses::CPose3D p2 
)
staticprotected

◆ alignOpticalWithMRPTFrame()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::alignOpticalWithMRPTFrame ( )
protected

Definition at line 1485 of file CGraphSlamEngine_impl.h.

References ASSERT_, DEG2RAD, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.

◆ computeMap()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::computeMap ( ) const
inline

Compute the map of the environment based on the recorded measurements.

Warning
Currently only mrpt::obs::2DRangeScans are supported
See also
getMap

Definition at line 893 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::format(), MRPT_END, MRPT_START, mrpt::system::now(), and THROW_EXCEPTION.

◆ computeSlamMetric()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::computeSlamMetric ( mrpt::utils::TNodeID  nodeID,
size_t  gt_index 
)
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 2337 of file CGraphSlamEngine_impl.h.

References MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.

◆ decimateLaserScan()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::decimateLaserScan ( mrpt::obs::CObservation2DRangeScan laser_scan_in,
mrpt::obs::CObservation2DRangeScan laser_scan_out,
const int  keep_every_n_entries = 2 
)
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

See also
updateMapVisualization

Definition at line 1894 of file CGraphSlamEngine_impl.h.

References mrpt::obs::CObservation2DRangeScan::loadFromVectors(), MRPT_END, MRPT_START, mrpt::obs::CObservation2DRangeScan::scan, mrpt::utils::ContainerReadOnlyProxyAccessor< STLCONTAINER >::size(), and mrpt::obs::CObservation2DRangeScan::validRange.

◆ dumpVisibilityErrorMsg()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::dumpVisibilityErrorMsg ( std::string  viz_flag,
int  sleep_time = 500 
)
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 1699 of file CGraphSlamEngine_impl.h.

References MRPT_END, MRPT_LOG_ERROR_STREAM, MRPT_START, and mrpt::system::sleep().

◆ execDijkstraNodesEstimation()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::execDijkstraNodesEstimation ( )
protected

Wrapper around the GRAPH_T::dijkstra_nodes_estimate.

Update the global position of the nodes

Definition at line 807 of file CGraphSlamEngine_impl.h.

◆ execGraphSlamStep()

template<class GRAPH_T >
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::execGraphSlamStep ( mrpt::obs::CObservationPtr &  observation,
size_t &  rawlog_entry 
)

Wrapper method around _execGraphSlamStep.

Handy for not having to specify any action/observations objects

Returns
False if the user has requested to exit the graphslam execution (e.g. pressed ctrl-c), True otherwise

Definition at line 485 of file CGraphSlamEngine_impl.h.

◆ generateReportFiles()

template<class GRAPH_T >
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.

Parameters
[in]output_dir_fnamedirectory name to generate the files in. Directory must be crated prior to this call
See also
getDescriptiveReport, CGraphSlamHandler::initOutputDir

Definition at line 2569 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::system::directoryExists(), mrpt::format(), MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ getCurrentRobotPosEstimation()

template<class GRAPH_T >
GRAPH_T::global_pose_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getCurrentRobotPosEstimation ( ) const

Query CGraphSlamEngine instance for the current estimated robot position.

Definition at line 94 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ getDeformationEnergyVector()

template<class GRAPH_T >
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.

Parameters
[out]vec_outdeformation energy vector to be filled
See also
m_deformation_energy_vec

Definition at line 2660 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ getDescriptiveReport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getDescriptiveReport ( std::string report_str) const
protected

Fill the provided string with a detailed report of the class state.

Report includes the following:

  • Timing of important methods
  • Properties fo class at the current time
  • Logging of commands until current time
Note
Decider/Optimizer classes should also implement a getDescriptiveReport method for printing information on their part of the execution.

Definition at line 2487 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ getGraph()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
const GRAPH_T& mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getGraph ( ) const
inline

Return a reference to the underlying GRAPH_T instance.

Definition at line 361 of file CGraphSlamEngine.h.

References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_graph.

◆ getGraphSlamStats()

template<class GRAPH_T >
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 2531 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, MRPT_END, and MRPT_START.

◆ getLSPoseForGridMapVisualization()

template<class GRAPH_T >
mrpt::poses::CPose3D mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getLSPoseForGridMapVisualization ( const mrpt::utils::TNodeID  nodeID) const
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 1750 of file CGraphSlamEngine_impl.h.

◆ getMap() [1/2]

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap ( mrpt::maps::COccupancyGridMap2DPtr  map,
mrpt::system::TTimeStamp acquisition_time = NULL 
) const

◆ getMap() [2/2]

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap ( mrpt::maps::COctoMapPtr  map,
mrpt::system::TTimeStamp acquisition_time = NULL 
) const

Definition at line 872 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_START, and THROW_EXCEPTION.

◆ getNodeIDsOfEstimatedTrajectory()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getNodeIDsOfEstimatedTrajectory ( std::set< mrpt::utils::TNodeID > *  nodes_set) const
virtual

Return the list of nodeIDs which make up robot trajectory.

See also
updateEstimatedTrajectoryVisualization

Definition at line 114 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ getParamsAsString() [1/2]

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getParamsAsString ( std::string params_out) const

Fill in the provided string with the class configuration parameters.

See also
printParams

Definition at line 1036 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ getParamsAsString() [2/2]

template<class GRAPH_T >
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getParamsAsString ( ) const

Wrapper around getParamsAsString.

Returns the generated string instead of passing it as an argument to the call

See also
printParams

Definition at line 1026 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ getRawlogFname()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getRawlogFname ( )
inline

Return the filename of the used rawlog file.

Definition at line 363 of file CGraphSlamEngine.h.

References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_rawlog_fname.

◆ getRobotEstimatedTrajectory()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getRobotEstimatedTrajectory ( typename GRAPH_T::global_poses_t *  graph_poses) const
virtual

Definition at line 104 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ getTimeStamp()

template<class GRAPH_T >
mrpt::system::TTimeStamp mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getTimeStamp ( const mrpt::obs::CActionCollectionPtr  action,
const mrpt::obs::CSensoryFramePtr  observations,
const mrpt::obs::CObservationPtr  observation 
)
staticprotected

Fill the TTimestamp in a consistent manner.

Method can be used in both MRPT Rawlog formats

Parameters
[in]action_ptrPointer to the action (action-observations format)
[in]observationsPointer to list of observations (action-observations format)
[in]observationPointer to single observation (observation-only format)
Note
if both action_ptr and observation_ptr contains valid timestamps, the action is preferred.
Returns
mrpt::system::TTimeStamp

Definition at line 1714 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, INVALID_TIMESTAMP, MRPT_END, and MRPT_START.

◆ initClass()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initClass ( )
protected

◆ initCurrPosViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initCurrPosViewport ( )
protected

Definition at line 1261 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ initEstimatedTrajectoryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initEstimatedTrajectoryVisualization ( )
protected

Definition at line 2074 of file CGraphSlamEngine_impl.h.

References ASSERT_, mrpt::mrpt::format(), MRPT_END, and MRPT_START.

◆ initGTVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initGTVisualization ( )
protected

Definition at line 1920 of file CGraphSlamEngine_impl.h.

References ASSERT_, mrpt::mrpt::format(), MRPT_END, and MRPT_START.

◆ initIntensityImageViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initIntensityImageViewport ( )
protected

Definition at line 1198 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ initMapVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initMapVisualization ( )
protected

Definition at line 1756 of file CGraphSlamEngine_impl.h.

◆ initOdometryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initOdometryVisualization ( )
protected

Definition at line 2000 of file CGraphSlamEngine_impl.h.

References ASSERT_, mrpt::mrpt::format(), MRPT_END, and MRPT_START.

◆ initRangeImageViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initRangeImageViewport ( )
protected

Definition at line 1135 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ initResultsFile()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initResultsFile ( const std::string fname)
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.

See also
CGraphSlamHandler::initOutputDir

Definition at line 1096 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::system::dateTimeToString(), mrpt::system::fileNameStripInvalidChars(), mrpt::mrpt::format(), mrpt::system::getCurrentLocalTime(), mrpt::system::getCurrentTime(), MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ initRobotModelVisualization()

template<class GRAPH_T >
mrpt::opengl::CSetOfObjectsPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initRobotModelVisualization ( )
protected

Definition at line 1241 of file CGraphSlamEngine_impl.h.

◆ initRobotModelVisualizationInternal() [1/2]

template<class GRAPH_T >
mrpt::opengl::CSetOfObjectsPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initRobotModelVisualizationInternal ( const mrpt::poses::CPose2D p_unused)
protected

Method to help overcome the partial template specialization restriction of C++.

Apply polymorphism by overloading function arguments instead

Definition at line 1248 of file CGraphSlamEngine_impl.h.

References mrpt::opengl::stock_objects::RobotPioneer().

◆ initRobotModelVisualizationInternal() [2/2]

template<class GRAPH_T >
mrpt::opengl::CSetOfObjectsPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initRobotModelVisualizationInternal ( const mrpt::poses::CPose3D p_unused)
protected

◆ initSlamMetricVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initSlamMetricVisualization ( )
protected

Definition at line 2431 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.

◆ initVisualization()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initVisualization ( )
protected

◆ isPaused()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::isPaused ( ) const
inline

◆ loadParams()

template<class GRAPH_T >
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 944 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::system::fileExists(), mrpt::mrpt::format(), MRPT_END, MRPT_LOG_INFO_STREAM, MRPT_START, mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_int(), and mrpt::utils::CConfigFileBase::read_string().

◆ monitorNodeRegistration()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::monitorNodeRegistration ( bool  registered = false,
std::string  class_name = "Class" 
)
protectedvirtual

Assert that the given nodes number matches the registered graph nodes, otherwise throw exception.

Note
Method locks the graph internally.

logic_error if the expected node count mismatches with the graph current node count.

Definition at line 818 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::format(), INVALID_NODEID, MRPT_END, MRPT_LOG_ERROR_STREAM, MRPT_START, and THROW_EXCEPTION.

◆ pauseExec()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec ( )
inline

◆ printParams()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::printParams ( ) const

Print the problem parameters to the console for verification.

Method is a wrapper around CGraphSlamEngine::getParamsAsString method

See also
getParamsAsString

Definition at line 1084 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ queryObserverForEvents()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::queryObserverForEvents ( )
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 1539 of file CGraphSlamEngine_impl.h.

References ASSERT_, ASSERTMSG_, MRPT_END, and MRPT_START.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec().

◆ readGTFile() [1/2]

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::readGTFile ( const std::string fname_GT,
std::vector< mrpt::poses::CPose2D > *  gt_poses,
std::vector< mrpt::system::TTimeStamp > *  gt_timestamps = NULL 
)
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.

See also
readGTFileRGBD_TUM
Parameters
[in]fname_GTGround truth filename from which the measurements are to be read
[out]gt_posesstd::vector which is to contain the 2D ground truth poses.
[out]gt_timestampsstd::vector which is to contain the timestamps for the corresponding ground truth poses. Ignore this argument if timestamps are not needed.

Definition at line 1313 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::utils::CFileInputStream::close(), mrpt::system::fileExists(), mrpt::utils::CFileInputStream::fileOpenCorrectly(), mrpt::format(), MRPT_END, MRPT_START, mrpt::utils::CFileInputStream::readLine(), and mrpt::system::tokenize().

◆ readGTFile() [2/2]

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::readGTFile ( const std::string fname_GT,
std::vector< mrpt::poses::CPose3D > *  gt_poses,
std::vector< mrpt::system::TTimeStamp > *  gt_timestamps = NULL 
)
static

Definition at line 1364 of file CGraphSlamEngine_impl.h.

References THROW_EXCEPTION.

◆ readGTFileRGBD_TUM()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::readGTFileRGBD_TUM ( const std::string fname_GT,
std::vector< mrpt::poses::CPose2D > *  gt_poses,
std::vector< mrpt::system::TTimeStamp > *  gt_timestamps = NULL 
)
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.

Parameters
[in]fname_GTGround truth filename from which the measurements are to be read
[out]gt_posesstd::vector which is to contain the 2D ground truth poses.
[out]gt_timestampsstd::vector which is to contain the timestamps for the corresponding ground truth poses. Ignore this argument if timestamps are not needed.
See also
readGTFile, http://www.mrpt.org/Collection_of_Kinect_RGBD_datasets_with_ground_truth_CVPR_TUM_2011

Definition at line 1372 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, mrpt::utils::CFileInputStream::close(), mrpt::system::fileExists(), mrpt::utils::CFileInputStream::fileOpenCorrectly(), mrpt::format(), MRPT_END, MRPT_START, mrpt::math::CQuaternion< T >::r(), mrpt::utils::CFileInputStream::readLine(), mrpt::math::CQuaternion< T >::rpy(), mrpt::system::tokenize(), mrpt::math::CQuaternion< T >::x(), mrpt::math::CQuaternion< T >::y(), and mrpt::math::CQuaternion< T >::z().

◆ resumeExec()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec ( ) const
inline

◆ save3DScene()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::save3DScene ( const std::string fname_in = NULL) const

Wrapper method around the COpenGLScene::saveToFile method.

Parameters
[in]Nameof the generated graph file - Defaults to "output_graph" if not set by the user
See also
saveGraph

Definition at line 2293 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_ERROR_STREAM, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ saveGraph()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::saveGraph ( const std::string fname_in = NULL) const

Wrapper method around the GRAPH_T::saveToTextFile method.

Method saves the graph in the format used by TORO & HoG-man strategies

Parameters
[in]fname_inName of the generated graph file - Defaults to "output_graph" if not set by the user
See also
save3DScene, http://www.mrpt.org/Robotics_file_formats

Definition at line 2272 of file CGraphSlamEngine_impl.h.

References MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ setCurrentPositionModel()

template<class GRAPH_T >
mrpt::opengl::CSetOfObjectsPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::setCurrentPositionModel ( const std::string model_name,
const mrpt::utils::TColor model_color = mrpt::utils::TColor(0,0,0),
const size_t  model_size = 1,
const pose_t init_pose = pose_t() 
)
protected

Set the opengl model that indicates the latest position of the trajectory at hand.

Parameters
[in]model_nameName of the resulting opengl object.
[in]model_colorColor of the object.
[in]model_sizeScaling of the object.
[in]init_poseInitial position of the object.
Todo:
Use an airplane/quad model for 3D operations
Returns
CSetOfObjectsPtr instance.
Note
Different model is used depending on whether we are running 2D or 3D SLAM.

Definition at line 2639 of file CGraphSlamEngine_impl.h.

References ASSERTMSG_, and model.

◆ setObjectPropsFromNodeID()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::setObjectPropsFromNodeID ( const mrpt::utils::TNodeID  nodeID,
mrpt::opengl::CSetOfObjectsPtr &  viz_object 
)
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.

Note
Base class method sets only the color of the object

Definition at line 1885 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ toggleEstimatedTrajectoryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::toggleEstimatedTrajectoryVisualization ( )
protected

Definition at line 1672 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ toggleGTVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::toggleGTVisualization ( )
protected

Definition at line 1607 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ toggleMapVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::toggleMapVisualization ( )
protected

Definition at line 1634 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ toggleOdometryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::toggleOdometryVisualization ( )
protected

Definition at line 1581 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.

◆ togglePause()

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::togglePause ( )
inline

◆ updateAllVisuals()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateAllVisuals ( )
protected

Wrapper around the deciders/optimizer updateVisuals methods.

Definition at line 1155 of file CGraphSlamEngine_impl.h.

References MRPT_END, and MRPT_START.

◆ updateCurrPosViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateCurrPosViewport ( )
inlineprotectedvirtual

Update the viewport responsible for displaying the graph-building procedure in the estimated position of the robot.

Definition at line 1290 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.

◆ updateEstimatedTrajectoryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateEstimatedTrajectoryVisualization ( bool  full_update = false)
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 2123 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ updateGTVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateGTVisualization ( )
protected

Display the next ground truth position in the visualization window.

See also
updateOdometryVisualization

Definition at line 1967 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ updateIntensityImageViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateIntensityImageViewport ( )
protected

In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport.

Definition at line 1217 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ updateMapVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateMapVisualization ( const std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > &  nodes_to_laser_scans2D,
bool  full_update = false 
)
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.

See also
updateEstimatedTrajectoryVisualization

Definition at line 1768 of file CGraphSlamEngine_impl.h.

References ASSERT_, mrpt::maps::CPointsMap::getAs3DObject(), mrpt::maps::CMetricMap::insertObservation(), MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_START, mrpt::utils::CTicTac::Tac(), and mrpt::utils::CTicTac::Tic().

◆ updateOdometryVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateOdometryVisualization ( )
protected

Update odometry-only cloud with latest odometry estimation.

See also
updateGTVisualization

Definition at line 2043 of file CGraphSlamEngine_impl.h.

References ASSERT_, ASSERTMSG_, MRPT_END, and MRPT_START.

◆ updateRangeImageViewport()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateRangeImageViewport ( )
protected

In RGB-D TUM Datasets update the Range image displayed in a seperate viewport.

Definition at line 1169 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

◆ updateSlamMetricVisualization()

template<class GRAPH_T >
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::updateSlamMetricVisualization ( )
protected

Update the displayPlots window with the new information with regards to the metric.

Definition at line 2455 of file CGraphSlamEngine_impl.h.

References ASSERT_, MRPT_END, and MRPT_START.

Member Data Documentation

◆ header_sep

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
const std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::header_sep = std::string(80, '-')
staticprotected

Separator string to be used in debugging messages.

Definition at line 1013 of file CGraphSlamEngine.h.

◆ m_class_name

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_class_name
protected

Definition at line 996 of file CGraphSlamEngine.h.

◆ m_config_fname

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_config_fname
protected

Definition at line 760 of file CGraphSlamEngine.h.

◆ m_curr_deformation_energy

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_curr_deformation_energy
protected

Definition at line 929 of file CGraphSlamEngine.h.

◆ m_curr_odometry_only_pose

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
pose_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_curr_odometry_only_pose
protected

Current robot position based solely on odometry.

Definition at line 969 of file CGraphSlamEngine.h.

◆ m_curr_timestamp

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::system::TTimeStamp mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_curr_timestamp
protected

Current dataset timestamp.

Definition at line 967 of file CGraphSlamEngine.h.

◆ m_current_constraint_type

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_current_constraint_type
protected

Type of constraint currently in use.

Definition at line 1009 of file CGraphSlamEngine.h.

◆ m_current_constraint_type_color

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TColor mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_current_constraint_type_color
protected

Definition at line 898 of file CGraphSlamEngine.h.

◆ m_dataset_grab_time

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_dataset_grab_time
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 962 of file CGraphSlamEngine.h.

◆ m_deformation_energy_vec

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::vector<double> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_deformation_energy_vec
protected

Definition at line 930 of file CGraphSlamEngine.h.

◆ m_edge_counter

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::detail::CEdgeCounter mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_edge_counter
protected

Instance to keep track of all the edges + visualization related operations.

Definition at line 865 of file CGraphSlamEngine.h.

◆ m_edge_reg

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::deciders::CEdgeRegistrationDecider<GRAPH_T>* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_edge_reg
protected

Definition at line 753 of file CGraphSlamEngine.h.

◆ m_enable_curr_pos_viewport

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_curr_pos_viewport
protected

Definition at line 810 of file CGraphSlamEngine.h.

◆ m_enable_intensity_viewport

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_intensity_viewport
protected

Definition at line 811 of file CGraphSlamEngine.h.

◆ m_enable_range_viewport

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_range_viewport
protected

Definition at line 812 of file CGraphSlamEngine.h.

◆ m_enable_visuals

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
const bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_visuals
protected

Determine if we are to enable visualization support or not.

Definition at line 758 of file CGraphSlamEngine.h.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().

◆ m_estimated_traj_color

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TColor mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_estimated_traj_color
protected

Definition at line 896 of file CGraphSlamEngine.h.

◆ m_first_laser_scan2D

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::obs::CObservation2DRangeScanPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_first_laser_scan2D
protected

First recorded laser scan - assigned to the root.

Definition at line 887 of file CGraphSlamEngine.h.

◆ m_fname_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_fname_GT
protected

Definition at line 768 of file CGraphSlamEngine.h.

◆ m_graph

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
GRAPH_T mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_graph
protected

The graph object to be built and optimized.

Definition at line 746 of file CGraphSlamEngine.h.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getGraph().

◆ m_graph_section

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::synch::CCriticalSection mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_graph_section
protected

Mark graph modification/accessing explicitly for multithreaded implementation.

Definition at line 915 of file CGraphSlamEngine.h.

◆ m_gridmap_cached

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::maps::COccupancyGridMap2DPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_gridmap_cached
mutableprotected

Definition at line 980 of file CGraphSlamEngine.h.

◆ m_GT_color

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TColor mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_GT_color
protected

Definition at line 895 of file CGraphSlamEngine.h.

◆ m_GT_file_format

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_GT_file_format
protected

Definition at line 878 of file CGraphSlamEngine.h.

◆ m_GT_poses

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::vector<pose_t> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_GT_poses
protected

Definition at line 876 of file CGraphSlamEngine.h.

◆ m_GT_poses_index

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
size_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_GT_poses_index
protected

Counter for reading back the GT_poses.

Definition at line 771 of file CGraphSlamEngine.h.

◆ m_GT_poses_step

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
size_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_GT_poses_step
protected

Rate at which to read the GT poses.

Definition at line 773 of file CGraphSlamEngine.h.

◆ m_has_read_config

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_has_read_config
protected

Definition at line 777 of file CGraphSlamEngine.h.

◆ m_img_external_storage_dir

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_img_external_storage_dir
protected

Definition at line 919 of file CGraphSlamEngine.h.

◆ m_img_prev_path_base

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_img_prev_path_base
protected

Definition at line 920 of file CGraphSlamEngine.h.

◆ m_info_params

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
struct mrpt::graphslam::CGraphSlamEngine::TRGBDInfoFileParams mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_info_params
protected

◆ m_init_timestamp

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::system::TTimeStamp mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_init_timestamp
protected

First recorded timestamp in the dataset.

Definition at line 965 of file CGraphSlamEngine.h.

◆ m_is_first_time_node_reg

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_is_first_time_node_reg
protected

Track the first node registration occurance.

Handy so that we can assign a measurement to the root node as well.

Definition at line 1001 of file CGraphSlamEngine.h.

◆ m_is_paused

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_is_paused
mutableprotected

◆ m_keystroke_estimated_trajectory

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_estimated_trajectory
protected

Definition at line 858 of file CGraphSlamEngine.h.

◆ m_keystroke_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_GT
protected

Definition at line 857 of file CGraphSlamEngine.h.

◆ m_keystroke_map

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_map
protected

Definition at line 859 of file CGraphSlamEngine.h.

◆ m_keystroke_odometry

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_odometry
protected

Definition at line 856 of file CGraphSlamEngine.h.

◆ m_keystroke_pause_exec

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_pause_exec
protected

◆ m_last_laser_scan2D

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::obs::CObservation2DRangeScanPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_last_laser_scan2D
protected

Last laser scan that the current class instance received.

Definition at line 885 of file CGraphSlamEngine.h.

◆ m_last_laser_scan3D

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::obs::CObservation3DRangeScanPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_last_laser_scan3D
protected

Last laser scan that the current class instance received.

Definition at line 890 of file CGraphSlamEngine.h.

◆ m_map_acq_time

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::system::TTimeStamp mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_map_acq_time
mutableprotected

Timestamp at which the map was computed.

Note
Common var for both 2D and 3D maps.

Definition at line 993 of file CGraphSlamEngine.h.

◆ m_map_is_cached

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_map_is_cached
mutableprotected

Indicates if the map is cached.

Note
Common var for both 2D and 3D maps.

Definition at line 988 of file CGraphSlamEngine.h.

◆ m_node_reg

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::deciders::CNodeRegistrationDecider<GRAPH_T>* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_node_reg
protected

Definition at line 752 of file CGraphSlamEngine.h.

◆ m_nodeID_max

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TNodeID mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_nodeID_max
protected

Internal counter for querying for the number of nodeIDs.

Handy for not locking the m_graph resource

Definition at line 911 of file CGraphSlamEngine.h.

◆ m_nodeID_to_gt_indices

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::map<mrpt::utils::TNodeID, size_t> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_nodeID_to_gt_indices
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 928 of file CGraphSlamEngine.h.

◆ m_nodes_to_laser_scans2D

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
nodes_to_scans2D_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_nodes_to_laser_scans2D
protected

Map of NodeIDs to their corresponding LaserScans.

Definition at line 882 of file CGraphSlamEngine.h.

◆ m_observation_only_dataset

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_observation_only_dataset
protected

Definition at line 778 of file CGraphSlamEngine.h.

◆ m_octomap_cached

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::maps::COctoMapPtr mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_octomap_cached
mutableprotected

Definition at line 983 of file CGraphSlamEngine.h.

◆ m_odometry_color

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TColor mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_odometry_color
protected

Definition at line 894 of file CGraphSlamEngine.h.

◆ m_odometry_poses

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::vector<pose_t> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_odometry_poses
protected

Definition at line 875 of file CGraphSlamEngine.h.

◆ m_offset_x_left

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_x_left
protected

Offset from the left side of the canvas.

Common for all the messages that are displayed on that side.

Definition at line 833 of file CGraphSlamEngine.h.

◆ m_offset_y_current_constraint_type

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_current_constraint_type
protected

Definition at line 839 of file CGraphSlamEngine.h.

◆ m_offset_y_estimated_traj

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_estimated_traj
protected

Definition at line 837 of file CGraphSlamEngine.h.

◆ m_offset_y_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_GT
protected

Definition at line 836 of file CGraphSlamEngine.h.

◆ m_offset_y_odometry

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_odometry
protected

Definition at line 835 of file CGraphSlamEngine.h.

◆ m_offset_y_paused_message

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_paused_message
protected

Definition at line 840 of file CGraphSlamEngine.h.

◆ m_offset_y_timestamp

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
double mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_offset_y_timestamp
protected

Definition at line 838 of file CGraphSlamEngine.h.

◆ m_optimized_map_color

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::TColor mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_optimized_map_color
protected

Definition at line 897 of file CGraphSlamEngine.h.

◆ m_optimizer

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::optimizers::CGraphSlamOptimizer<GRAPH_T>* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_optimizer
protected

Definition at line 754 of file CGraphSlamEngine.h.

◆ m_out_streams

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
fstreams_out mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_out_streams
protected

keeps track of the out fstreams so that they can be closed (if still open) in the class Dtor.

Definition at line 783 of file CGraphSlamEngine.h.

◆ m_paused_message

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
const std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_paused_message
protected

Message to be displayed while paused.

Definition at line 820 of file CGraphSlamEngine.h.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec().

◆ m_rawlog_fname

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_rawlog_fname
protected

Rawlog file from which to read the measurements.

If string is empty, process is to be run online

Definition at line 766 of file CGraphSlamEngine.h.

Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getRawlogFname().

◆ m_request_to_exit

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_request_to_exit
protected

Indicate whether the user wants to exit the application (e.g.

pressed by pressign ctrl-c)

Definition at line 974 of file CGraphSlamEngine.h.

◆ m_robot_model_size

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
size_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_robot_model_size
protected

How big are the robots going to be in the scene.

Definition at line 906 of file CGraphSlamEngine.h.

◆ m_rot_TUM_to_MRPT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::math::CMatrixDouble33 mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_rot_TUM_to_MRPT
protected

Definition at line 904 of file CGraphSlamEngine.h.

◆ m_simple_map_cached

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::maps::CSimpleMap mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_simple_map_cached
mutableprotected

Acquired map in CSimpleMap representation.

Definition at line 982 of file CGraphSlamEngine.h.

◆ m_supported_constraint_types

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
std::vector<std::string> mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_supported_constraint_types
protected

MRPT CNetworkOfPoses constraint classes that are currently supported.

Definition at line 1006 of file CGraphSlamEngine.h.

◆ m_text_index_current_constraint_type

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_current_constraint_type
protected

Definition at line 846 of file CGraphSlamEngine.h.

◆ m_text_index_estimated_traj

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_estimated_traj
protected

Definition at line 844 of file CGraphSlamEngine.h.

◆ m_text_index_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_GT
protected

Definition at line 843 of file CGraphSlamEngine.h.

◆ m_text_index_odometry

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_odometry
protected

Definition at line 842 of file CGraphSlamEngine.h.

◆ m_text_index_paused_message

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_paused_message
protected

◆ m_text_index_timestamp

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_timestamp
protected

Definition at line 845 of file CGraphSlamEngine.h.

◆ m_time_logger

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::utils::CTimeLogger mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_time_logger
protected

Time logger instance.

Definition at line 743 of file CGraphSlamEngine.h.

◆ m_use_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_use_GT
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 872 of file CGraphSlamEngine.h.

◆ m_user_decides_about_output_dir

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_user_decides_about_output_dir
protected

Definition at line 775 of file CGraphSlamEngine.h.

◆ m_visualize_estimated_trajectory

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_visualize_estimated_trajectory
protected

Definition at line 808 of file CGraphSlamEngine.h.

◆ m_visualize_GT

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_visualize_GT
protected

Definition at line 806 of file CGraphSlamEngine.h.

◆ m_visualize_map

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_visualize_map
protected

Definition at line 807 of file CGraphSlamEngine.h.

◆ m_visualize_odometry_poses

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_visualize_odometry_poses
protected

Definition at line 805 of file CGraphSlamEngine.h.

◆ m_visualize_SLAM_metric

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
bool mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_visualize_SLAM_metric
protected

Definition at line 809 of file CGraphSlamEngine.h.

◆ m_win

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::gui::CDisplayWindow3D* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win
protected

◆ m_win_manager

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::CWindowManager* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win_manager
protected

Definition at line 787 of file CGraphSlamEngine.h.

◆ m_win_observer

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::graphslam::CWindowObserver* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win_observer
protected

Definition at line 789 of file CGraphSlamEngine.h.

◆ m_win_plot

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
mrpt::gui::CDisplayWindowPlots* mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win_plot
protected

DisplayPlots instance for visualizing the evolution of the SLAM metric.

Definition at line 793 of file CGraphSlamEngine.h.

◆ report_sep

template<class GRAPH_T = typename mrpt::graphs::CNetworkOfPoses2DInf>
const std::string mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::report_sep = std::string(2, '\n')
staticprotected

Definition at line 1014 of file CGraphSlamEngine.h.




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