139 template <
class GRAPH_T = 
typename mrpt::graphs::CNetworkOfPoses2DInf>
   144     using fstreams_out = std::map<std::string, mrpt::io::CFileOutputStream>;
   151     using pose_t = 
typename GRAPH_T::constraint_t::type_value;
   184         const std::string& config_file, 
const std::string& rawlog_fname = 
"",
   185         const std::string& fname_GT = 
"",
   205         std::set<mrpt::graphs::TNodeID>* nodes_set) 
const;
   215     void saveGraph(
const std::string* fname_in = 
nullptr) 
const;
   224     void save3DScene(
const std::string* fname_in = 
nullptr) 
const;
   327         const std::string& fname_GT,
   328         std::vector<mrpt::poses::CPose2D>* gt_poses,
   329         std::vector<mrpt::system::TTimeStamp>* gt_timestamps = 
nullptr);
   331         const std::string& fname_GT,
   332         std::vector<mrpt::poses::CPose3D>* gt_poses,
   333         std::vector<mrpt::system::TTimeStamp>* gt_timestamps = 
nullptr);
   353         const std::string& fname_GT,
   354         std::vector<mrpt::poses::CPose2D>* gt_poses,
   355         std::vector<mrpt::system::TTimeStamp>* gt_timestamps = 
nullptr);
   379         std::map<std::string, int>* node_stats,
   380         std::map<std::string, int>* edge_stats,
   420             "Program is paused. "   423             << 
"\" in the dipslay window to resume");
   433             std::this_thread::sleep_for(1s);
   551             nodes_to_laser_scans2D,
   552         bool full_update = 
false);
   601         const int keep_every_n_entries = 2);
   627         std::string viz_flag, 
int sleep_time = 500 );
   674         const std::string& model_name,
   676         const size_t model_size = 1, 
const pose_t& init_pose = 
pose_t());
   687         bool registered = 
false, std::string class_name = 
"Class");
   746     std::unique_ptr<mrpt::gui::CDisplayWindowPlots> 
m_win_plot = 
nullptr;
   908         std::map<std::string, std::string> 
fields;
 void updateOdometryVisualization()
Update odometry-only cloud with latest odometry estimation. 
 
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. 
 
double m_offset_y_paused_message
 
typename GRAPH_T::global_pose_t global_pose_t
 
virtual void getNodeIDsOfEstimatedTrajectory(std::set< mrpt::graphs::TNodeID > *nodes_set) const
Return the list of nodeIDs which make up robot trajectory. 
 
CGraphSlamEngine(const std::string &config_file, const std::string &rawlog_fname="", const std::string &fname_GT="", mrpt::graphslam::CWindowManager *win_manager=nullptr, mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > *node_reg=nullptr, mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > *edge_reg=nullptr, mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > *optimizer=nullptr)
Constructor of CGraphSlamEngine class template. 
 
int m_text_index_timestamp
 
void queryObserverForEvents()
Query the observer instance for any user events. 
 
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > * m_edge_reg
 
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. 
 
mrpt::system::TTimeStamp m_init_timestamp
First recorded timestamp in the dataset. 
 
void parseFile()
Parse the RGBD information file to gain information about the rawlog file contents. 
 
std::string m_keystroke_estimated_trajectory
 
void save3DScene(const std::string *fname_in=nullptr) const
Wrapper method around the COpenGLScene::saveToFile method. 
 
mrpt::gui::CDisplayWindow3D * m_win
 
mrpt::obs::CObservation3DRangeScan::Ptr m_last_laser_scan3D
Last laser scan that the current class instance received. 
 
bool getGraphSlamStats(std::map< std::string, int > *node_stats, std::map< std::string, int > *edge_stats, mrpt::system::TTimeStamp *timestamp=nullptr)
Fill the given maps with stats regarding the overall execution of graphslam. 
 
bool m_enable_curr_pos_viewport
 
void updateGTVisualization()
Display the next ground truth position in the visualization window. 
 
void computeMap() const
Compute the map of the environment based on the recorded measurements. 
 
void toggleMapVisualization()
 
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
 
std::unique_ptr< mrpt::gui::CDisplayWindowPlots > m_win_plot
DisplayPlots instance for visualizing the evolution of the SLAM metric. 
 
void updateSlamMetricVisualization()
Update the displayPlots window with the new information with regards to the metric. 
 
double m_offset_y_timestamp
 
~TRGBDInfoFileParams()=default
 
Interface for implementing node registration classes. 
 
void initOdometryVisualization()
 
double m_dataset_grab_time
Time it took to record the dataset. 
 
bool m_use_GT
Flag for specifying if we are going to use ground truth data at all. 
 
double m_offset_x_left
Offset from the left side of the canvas. 
 
std::string m_keystroke_GT
 
std::string getRawlogFname()
Return the filename of the used rawlog file. 
 
mrpt::maps::CSimpleMap m_simple_map_cached
Acquired map in CSimpleMap representation. 
 
mrpt::maps::COccupancyGridMap2D::Ptr m_gridmap_cached
 
global_pose_t getCurrentRobotPosEstimation() const
 
std::map< mrpt::graphs::TNodeID, mrpt::obs::CObservation2DRangeScan::Ptr > nodes_to_scans2D_t
 
void initRangeImageViewport()
 
mrpt::img::TColor m_odometry_color
 
Interface for implementing edge registration classes. 
 
bool m_request_to_exit
Indicate whether the user wants to exit the application (e.g. 
 
double m_offset_y_current_constraint_type
 
mrpt::img::TColor m_GT_color
 
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...
 
void initGTVisualization()
 
mrpt::math::CMatrixDouble33 m_rot_TUM_to_MRPT
 
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
 
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...
 
void loadParams(const std::string &fname)
Read the configuration variables from the .ini file specified by the user. 
 
void computeSlamMetric(mrpt::graphs::TNodeID nodeID, size_t gt_index)
Compare the SLAM result (estimated trajectory) with the GT path. 
 
std::string m_rawlog_fname
Rawlog file from which to read the measurements. 
 
void updateAllVisuals()
Wrapper around the deciders/optimizer updateVisuals methods. 
 
mrpt::Clock::time_point TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
 
bool m_observation_only_dataset
 
SLAM methods related to graphs of pose constraints. 
 
static double accumulateAngleDiffs(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
 
mrpt::obs::CObservation2DRangeScan::Ptr m_first_laser_scan2D
First recorded laser scan - assigned to the root. 
 
static const std::string report_sep
 
typename GRAPH_T::constraint_t::type_value pose_t
Type of underlying poses (2D/3D). 
 
Generic class for tracking the total number of edges for different tpes of edges and for storing visu...
 
void alignOpticalWithMRPTFrame()
 
void initTRGBDInfoFileParams()
 
void execDijkstraNodesEstimation()
Wrapper around the GRAPH_T::dijkstra_nodes_estimate. 
 
void updateIntensityImageViewport()
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport. 
 
struct mrpt::graphslam::CGraphSlamEngine::TRGBDInfoFileParams m_info_params
 
Versatile class for consistent logging and management of output messages. 
 
size_t m_GT_poses_step
Rate at which to read the GT poses. 
 
bool m_is_first_time_node_reg
Track the first node registration occurance. 
 
std::map< std::string, std::string > fields
Format for the parameters in the info file: string literal - related value (kept in a string represen...
 
mrpt::img::TColor m_estimated_traj_color
 
bool m_visualize_estimated_trajectory
 
Main file for the GraphSlamEngine. 
 
const bool m_enable_visuals
Determine if we are to enable visualization support or not. 
 
std::vector< pose_t > m_odometry_poses
 
virtual void updateCurrPosViewport()
Update the viewport responsible for displaying the graph-building procedure in the estimated position...
 
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++. 
 
mrpt::graphslam::CWindowObserver * m_win_observer
 
void updateEstimatedTrajectoryVisualization(bool full_update=false)
Update the Esstimated robot trajectory with the latest estimated robot position. 
 
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_T > * m_optimizer
 
double m_curr_deformation_energy
 
void initEstimatedTrajectoryVisualization()
 
mrpt::img::TColor m_current_constraint_type_color
 
const GRAPH_T & getGraph() const
Return a reference to the underlying GRAPH_T instance. 
 
mrpt::obs::CObservation2DRangeScan::Ptr m_last_laser_scan2D
Last laser scan that the current class instance received. 
 
void saveGraph(const std::string *fname_in=nullptr) const
Wrapper method around the GRAPH_T::saveToTextFile method. 
 
void getDescriptiveReport(std::string *report_str) const
Fill the provided string with a detailed report of the class state. 
 
static const std::string header_sep
Separator string to be used in debugging messages. 
 
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const mrpt::graphs::TNodeID nodeID) const
return the 3D Pose of a LaserScan that is to be visualized. 
 
void toggleEstimatedTrajectoryVisualization()
 
void initIntensityImageViewport()
 
std::vector< double > m_deformation_energy_vec
 
void toggleOdometryVisualization()
 
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. 
 
std::string m_img_external_storage_dir
 
mrpt::opengl::CSetOfObjects::Ptr initRobotModelVisualization()
 
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
 
void initMapVisualization()
 
bool m_user_decides_about_output_dir
 
void printParams() const
Print the problem parameters to the console for verification. 
 
mrpt::graphslam::CWindowManager * m_win_manager
 
double m_offset_y_estimated_traj
 
mrpt::graphslam::detail::CEdgeCounter m_edge_counter
Instance to keep track of all the edges + visualization related operations. 
 
void addTextMessage(const double x_frac, const double y_frac, const std::string &text, const size_t unique_index=0, const mrpt::opengl::TFontParams &fontParams=mrpt::opengl::TFontParams())
A shortcut for calling mrpt::opengl::COpenGLViewport::addTextMessage() in the "main" viewport of the ...
 
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
 
pose_t m_curr_odometry_only_pose
Current robot position based solely on odometry. 
 
GRAPH_T m_graph
The graph object to be built and optimized. 
 
virtual GRAPH_T::global_poses_t getRobotEstimatedTrajectory() const
 
int m_text_index_estimated_traj
 
bool m_enable_intensity_viewport
 
double m_offset_y_odometry
 
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats. 
 
std::string m_GT_file_format
 
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. 
 
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
 
A class used to store a 3D pose (a 3D translation + a rotation in 3D). 
 
std::string m_keystroke_pause_exec
 
Monitor events in the visualization window. 
 
void setRawlogFile(const std::string &rawlog_fname)
 
bool m_is_paused
Indicated if program is temporarily paused by the user. 
 
size_t m_GT_poses_index
Counter for reading back the GT_poses. 
 
mrpt::graphs::TNodeID m_nodeID_max
Internal counter for querying for the number of nodeIDs. 
 
mrpt::system::TTimeStamp m_curr_timestamp
Current dataset timestamp. 
 
std::string upperCase(const std::string &str)
Returns a upper-case version of a string. 
 
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. 
 
void getDeformationEnergyVector(std::vector< double > *vec_out) const
Fill the given vector with the deformation energy values computed for the SLAM evaluation metric...
 
std::string m_img_prev_path_base
 
std::vector< pose_t > m_GT_poses
 
bool m_visualize_odometry_poses
 
static void readGTFileRGBD_TUM(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=nullptr)
Parse the ground truth .txt file and fill in the corresponding m_GT_poses vector. ...
 
const std::string m_paused_message
Message to be displayed while paused. 
 
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities. 
 
typename GRAPH_T::constraint_t constraint_t
Type of graph constraints. 
 
mrpt::maps::COctoMap::Ptr m_octomap_cached
 
bool execGraphSlamStep(mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
Wrapper method around _execGraphSlamStep. 
 
std::string m_keystroke_odometry
 
fstreams_out m_out_streams
keeps track of the out fstreams so that they can be closed (if still open) in the class Dtor...
 
void toggleGTVisualization()
 
mrpt::img::TColor m_optimized_map_color
 
std::vector< std::string > m_supported_constraint_types
MRPT CNetworkOfPoses constraint classes that are currently supported. 
 
std::string getParamsAsString() const
Wrapper around getParamsAsString. 
 
size_t m_robot_model_size
How big are the robots going to be in the scene. 
 
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_T > * m_node_reg
 
static void readGTFile(const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=nullptr)
Parse the ground truth .txt file and fill in the corresponding gt_poses vector. 
 
Struct responsible for keeping the parameters of the .info file in RGBD related datasets. 
 
bool m_visualize_SLAM_metric
 
std::string m_current_constraint_type
Type of constraint currently in use. 
 
void initCurrPosViewport()
 
~CGraphSlamEngine() override
 
int m_text_index_paused_message
 
void dumpVisibilityErrorMsg(std::string viz_flag, int sleep_time=500)
Wrapper method that used for printing error messages in a consistent manner. 
 
mrpt::system::TTimeStamp m_map_acq_time
Timestamp at which the map was computed. 
 
typename fstreams_out::iterator fstreams_out_it
Map for iterating over output file streams. 
 
bool m_map_is_cached
Indicates if the map is cached. 
 
std::mutex m_graph_section
Mark graph modification/accessing explicitly for multithreaded implementation. 
 
void initSlamMetricVisualization()
 
void updateRangeImageViewport()
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport. 
 
Class acts as a container for storing pointers to mrpt::gui::CDisplayWindow3D, mrpt::graphslam::CWind...
 
std::string m_config_fname
 
mrpt::system::CTimeLogger m_time_logger
Time logger instance. 
 
std::string m_keystroke_map
 
int m_text_index_odometry
 
void generateReportFiles(const std::string &output_dir_fname_in)
Generate and write to a corresponding report for each of the respective self/decider/optimizer classe...
 
bool m_enable_range_viewport
 
void getMap(mrpt::maps::COccupancyGridMap2D::Ptr map, mrpt::system::TTimeStamp *acquisition_time=nullptr) const
 
std::map< mrpt::graphs::TNodeID, size_t > m_nodeID_to_gt_indices
Map from nodeIDs to their corresponding closest GT pose index. 
 
std::map< std::string, mrpt::io::CFileOutputStream > fstreams_out
Map for managing output file streams. 
 
nodes_to_scans2D_t m_nodes_to_laser_scans2D
Map of NodeIDs to their corresponding LaserScans. 
 
void initResultsFile(const std::string &fname)
Automate the creation and initialization of a results file relevant to the application. 
 
A graphical user interface (GUI) for efficiently rendering 3D scenes in real-time. 
 
void initClass()
General initialization method to call from the Class Constructors. 
 
int m_text_index_current_constraint_type