MRPT
2.0.1
|
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.
GRAPH_T | Graph Representation type - only CPosePDFGaussianInf has been tested at the moment |
Definition at line 140 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 > |
Map for managing output file streams. 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=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. More... | |
~CGraphSlamEngine () override | |
global_pose_t | getCurrentRobotPosEstimation () const |
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=nullptr) |
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=nullptr) const |
void | getMap (mrpt::maps::COctoMap::Ptr map, mrpt::system::TTimeStamp *acquisition_time=nullptr) 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 | |
static std::array< mrpt::system::TConsoleColor, NUMBER_OF_VERBOSITY_LEVELS > & | logging_levels_to_colors () |
Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor. More... | |
static std::array< std::string, NUMBER_OF_VERBOSITY_LEVELS > & | logging_levels_to_names () |
Map from VerbosityLevels to their corresponding names. More... | |
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=nullptr) |
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=nullptr) |
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. 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 {LVL_INFO} |
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 |
std::unique_ptr< mrpt::gui::CDisplayWindowPlots > | m_win_plot = nullptr |
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') |
Logging methods | |
void | logStr (const VerbosityLevel level, std::string_view 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=nullptr) 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 {true} |
[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 {false} |
[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 149 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::fstreams_out = std::map<std::string, mrpt::io::CFileOutputStream> |
Map for managing output file streams.
Definition at line 144 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 146 of file CGraphSlamEngine.h.
using mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::global_pose_t = typename GRAPH_T::global_pose_t |
Definition at line 152 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 154 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 151 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 = 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.
// 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. |
[in] | node_reg | Node Registration Decider to be used |
[in] | edge_reg | Edge Registration Decider to be used |
[in] | optimizer | Optimizer class to be used |
Definition at line 28 of file CGraphSlamEngine_impl.h.
References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::initClass().
|
override |
Definition at line 58 of file CGraphSlamEngine_impl.h.
References MRPT_LOG_DEBUG_STREAM, mrpt::img::CImage::setImagesPathBase(), and mrpt::system::strCmpI().
|
virtual |
Main class method responsible for parsing each measurement and for executing graphSLAM.
Definition at line 492 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, ASSERTDEBMSG_, 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().
|
staticprotected |
Definition at line 2480 of file CGraphSlamEngine_impl.h.
References mrpt::poses::CPose2D::phi(), and mrpt::math::wrapToPi().
|
staticprotected |
Definition at line 2486 of file CGraphSlamEngine_impl.h.
References mrpt::poses::CPose3D::pitch(), mrpt::poses::CPose3D::roll(), mrpt::math::wrapToPi(), and mrpt::poses::CPose3D::yaw().
|
protected |
Definition at line 1524 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.
|
inline |
Compute the map of the environment based on the recorded measurements.
Definition at line 937 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::format(), MRPT_END, MRPT_START, mrpt::system::now(), and THROW_EXCEPTION.
|
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 2409 of file CGraphSlamEngine_impl.h.
References MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.
|
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 1962 of file CGraphSlamEngine_impl.h.
References mrpt::obs::CObservation2DRangeScan::getScanRange(), mrpt::obs::CObservation2DRangeScan::getScanRangeValidity(), mrpt::obs::CObservation2DRangeScan::getScanSize(), mrpt::obs::CObservation2DRangeScan::loadFromVectors(), MRPT_END, and MRPT_START.
|
inherited |
Dump the current contents of the COutputLogger instance in the terminal window.
Definition at line 190 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 1746 of file CGraphSlamEngine_impl.h.
References MRPT_END, MRPT_LOG_ERROR_STREAM, and MRPT_START.
|
protected |
Wrapper around the GRAPH_T::dijkstra_nodes_estimate.
Update the global position of the nodes
Definition at line 839 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 479 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 2643 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::system::directoryExists(), mrpt::format(), MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
GRAPH_T::global_pose_t mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getCurrentRobotPosEstimation | ( | ) | const |
Definition at line 70 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 2741 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 2555 of file CGraphSlamEngine_impl.h.
References MRPT_END, and MRPT_START.
|
inline |
Return a reference to the underlying GRAPH_T instance.
Definition at line 303 of file CGraphSlamEngine.h.
References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_graph.
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 = nullptr |
||
) |
Fill the given maps with stats regarding the overall execution of graphslam.
Definition at line 2604 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, MRPT_END, and MRPT_START.
|
inherited |
Fill the provided string with the contents of the logger's history in std::string representation.
Definition at line 154 of file COutputLogger.cpp.
|
inherited |
Get the history of COutputLogger instance in a string representation.
Definition at line 159 of file COutputLogger.cpp.
Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::getDescriptiveReport().
|
inherited |
Return the last Tmsg instance registered in the logger history.
Definition at line 195 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 201 of file COutputLogger.cpp.
|
inherited |
Return the name of the COutputLogger instance.
Definition at line 143 of file COutputLogger.cpp.
|
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 1805 of file CGraphSlamEngine_impl.h.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap | ( | mrpt::maps::COccupancyGridMap2D::Ptr | map, |
mrpt::system::TTimeStamp * | acquisition_time = nullptr |
||
) | const |
Definition at line 885 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, mrpt::maps::COccupancyGridMap2D::Create(), MRPT_END, and MRPT_START.
void mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getMap | ( | mrpt::maps::COctoMap::Ptr | map, |
mrpt::system::TTimeStamp * | acquisition_time = nullptr |
||
) | const |
Definition at line 912 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_START, and THROW_EXCEPTION.
|
inlineinherited |
Definition at line 201 of file system/COutputLogger.h.
References mrpt::system::COutputLogger::m_min_verbosity_level.
Referenced by mrpt::apps::RawlogGrabberApp::dump_verbose_info(), mrpt::maps::CRandomFieldGridMap2D::isEnabledVerbose(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), and mrpt::apps::ICP_SLAM_App_Base::run().
|
virtual |
Return the list of nodeIDs which make up robot trajectory.
Definition at line 85 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_.
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 1058 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
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
Definition at line 1047 of file CGraphSlamEngine_impl.h.
References MRPT_END, and MRPT_START.
|
inline |
Return the filename of the used rawlog file.
Definition at line 305 of file CGraphSlamEngine.h.
References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_rawlog_fname.
|
virtual |
Definition at line 78 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 1761 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, INVALID_TIMESTAMP, MRPT_END, and MRPT_START.
|
protected |
General initialization method to call from the Class Constructors.
Definition at line 93 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, mrpt::maps::COctoMap::Create(), mrpt::maps::COccupancyGridMap2D::Create(), mrpt::system::extractFileDirectory(), mrpt::system::extractFileName(), mrpt::containers::find(), mrpt::img::CImage::getImagesPathBase(), INVALID_NODEID, INVALID_TIMESTAMP, MRPT_END, MRPT_LOG_INFO_STREAM, MRPT_LOG_WARN_STREAM, MRPT_START, mrpt::system::pause(), mrpt::img::CImage::setImagesPathBase(), mrpt::system::strCmpI(), and THROW_EXCEPTION.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::CGraphSlamEngine().
|
protected |
Definition at line 1290 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Definition at line 2144 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Definition at line 1993 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Definition at line 1219 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Definition at line 1812 of file CGraphSlamEngine_impl.h.
|
protected |
Definition at line 2073 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Definition at line 1153 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
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 1120 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::system::dateTimeToString(), mrpt::system::fileNameStripInvalidChars(), mrpt::format(), getCurrentTime(), MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
protected |
Definition at line 1266 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 1274 of file CGraphSlamEngine_impl.h.
References mrpt::opengl::stock_objects::RobotPioneer().
|
protected |
Definition at line 1283 of file CGraphSlamEngine_impl.h.
References mrpt::opengl::stock_objects::CornerXYZ().
|
protected |
Definition at line 2500 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.
|
protected |
|
inlineinherited |
Definition at line 202 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 385 of file CGraphSlamEngine.h.
References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_is_paused.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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 989 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::system::fileExists(), mrpt::format(), MRPT_END, MRPT_START, mrpt::config::CConfigFileBase::read_bool(), mrpt::config::CConfigFileBase::read_int(), mrpt::config::CConfigFileBase::read_string(), and setMinLoggingLevel().
|
inherited |
Log the given message only if the condition is satisfied.
Definition at line 131 of file COutputLogger.cpp.
|
inherited |
Definition at line 291 of file COutputLogger.cpp.
References getAddress(), and mrpt::system::COutputLogger::m_listCallbacks.
|
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 91 of file COutputLogger.cpp.
Referenced by mrpt::hmtslam::CHMTSLAM::areaAbstraction(), 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(), mrpt::hmtslam::CHMTSLAM::thread_3D_viewer(), mrpt::hmtslam::CHMTSLAM::thread_LSLAM(), mrpt::hmtslam::CHMTSLAM::thread_TBI(), and CGraphSlamHandler< GRAPH_T >::~CGraphSlamHandler().
|
inherited |
Reset the contents of the logger instance.
Called upon construction.
Definition at line 206 of file COutputLogger.cpp.
References mrpt::system::LVL_INFO.
|
staticinherited |
Map from VerbosityLevels to their corresponding mrpt::system::TConsoleColor.
Handy for coloring the input based on the verbosity of the message
Definition at line 47 of file COutputLogger.cpp.
References logging_levels_to_colors.
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 60 of file COutputLogger.cpp.
References logging_levels_to_names.
Referenced by mrpt::system::COutputLogger::TMsg::getAsString().
|
inherited |
Definition at line 278 of file COutputLogger.cpp.
References mrpt::system::COutputLogger::m_listCallbacks.
|
inherited |
Main method to add the specified message string to the logger.
Definition at line 72 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(), mrpt::system::COutputLoggerStreamWrapper::~COutputLoggerStreamWrapper(), and mrpt::system::CTimeLoggerSaveAtDtor::~CTimeLoggerSaveAtDtor().
|
protectedvirtual |
Assert that the given nodes number matches the registered graph nodes, otherwise throw exception.
logic_error if the expected node count mismatches with the graph current node count.
Definition at line 850 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::format(), INVALID_NODEID, MRPT_END, MRPT_LOG_ERROR_STREAM, MRPT_START, and THROW_EXCEPTION.
|
inline |
Definition at line 413 of file CGraphSlamEngine.h.
References mrpt::gui::CDisplayWindow3D::addTextMessage(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::isPaused(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_visuals, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_is_paused, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_keystroke_pause_exec, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_paused_message, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_paused_message, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win, MRPT_LOG_WARN_STREAM, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::queryObserverForEvents(), and mrpt::system::upperCase().
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::togglePause().
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
Definition at line 1107 of file CGraphSlamEngine_impl.h.
References MRPT_END, and MRPT_START.
|
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 1572 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, ASSERTDEBMSG_, MRPT_END, and MRPT_START.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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 1342 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::io::CFileInputStream::close(), mrpt::system::fileExists(), mrpt::io::CFileInputStream::fileOpenCorrectly(), mrpt::format(), mrpt::Clock::fromDouble(), MRPT_END, MRPT_START, mrpt::io::CFileInputStream::readLine(), and mrpt::system::tokenize().
|
static |
Definition at line 1400 of file CGraphSlamEngine_impl.h.
References THROW_EXCEPTION.
|
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 1408 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, mrpt::io::CFileInputStream::close(), mrpt::system::fileExists(), mrpt::io::CFileInputStream::fileOpenCorrectly(), mrpt::format(), mrpt::Clock::fromDouble(), MRPT_END, MRPT_START, mrpt::math::CQuaternion< T >::r(), mrpt::io::CFileInputStream::readLine(), and mrpt::system::tokenize().
|
inline |
Definition at line 397 of file CGraphSlamEngine.h.
References mrpt::gui::CDisplayWindow3D::addTextMessage(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::isPaused(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_enable_visuals, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_is_paused, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_text_index_paused_message, mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::m_win, and MRPT_LOG_INFO_STREAM.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::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 2358 of file CGraphSlamEngine_impl.h.
References ASSERTDEBMSG_, MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_LOG_ERROR_STREAM, MRPT_LOG_INFO_STREAM, and MRPT_START.
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 2335 of file CGraphSlamEngine_impl.h.
References MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
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 2726 of file CGraphSlamEngine_impl.h.
|
inherited |
Set the name of the COutputLogger instance.
Definition at line 138 of file COutputLogger.cpp.
Referenced by mrpt::slam::CMetricMapBuilderICP::CMetricMapBuilderICP(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::slam::CMonteCarloLocalization2D::CMonteCarloLocalization2D(), mrpt::slam::CMonteCarloLocalization3D::CMonteCarloLocalization3D(), mrpt::apps::ICP_SLAM_App_Base::ICP_SLAM_App_Base(), mrpt::apps::ICP_SLAM_App_Live::ICP_SLAM_App_Live(), mrpt::apps::ICP_SLAM_App_Rawlog::ICP_SLAM_App_Rawlog(), mrpt::graphslam::CWindowManager::initCWindowManager(), mrpt::apps::MonteCarloLocalization_Base::MonteCarloLocalization_Base(), mrpt::apps::RBPF_SLAM_App_Base::RBPF_SLAM_App_Base(), and mrpt::apps::RBPF_SLAM_App_Rawlog::RBPF_SLAM_App_Rawlog().
|
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 144 of file COutputLogger.cpp.
Referenced by mrpt::maps::CRandomFieldGridMap2D::enableVerbose(), mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute(), generic_kf_slam_test(), generic_pf_test(), generic_rbpf_slam_test(), mrpt::apps::RawlogGrabberApp::initialize(), mrpt::hwdrivers::CHokuyoURG::initialize(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), and mrpt::apps::ICP_SLAM_App_Base::run().
|
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 1952 of file CGraphSlamEngine_impl.h.
References MRPT_END, and MRPT_START.
|
inherited |
alias of setMinLoggingLevel()
Definition at line 149 of file COutputLogger.cpp.
Referenced by mrpt::nav::CAbstractNavigator::CAbstractNavigator(), mrpt::slam::CMetricMapBuilderRBPF::CMetricMapBuilderRBPF(), mrpt::comms::CServerTCPSocket::CServerTCPSocket(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), mrpt::math::ransac_detect_2D_lines(), and mrpt::apps::ICP_SLAM_App_Base::run().
|
protected |
Definition at line 1718 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
protected |
Definition at line 1649 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
protected |
Definition at line 1677 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
protected |
Definition at line 1621 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_INFO_STREAM, and MRPT_START.
|
inline |
Definition at line 386 of file CGraphSlamEngine.h.
References mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::isPaused(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().
|
protected |
Wrapper around the deciders/optimizer updateVisuals methods.
Definition at line 1174 of file CGraphSlamEngine_impl.h.
References MRPT_END, and MRPT_START.
|
inlineprotectedvirtual |
Update the viewport responsible for displaying the graph-building procedure in the estimated position of the robot.
Definition at line 1319 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_LOG_DEBUG_STREAM, and MRPT_START.
|
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 2192 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
Display the next ground truth position in the visualization window.
Definition at line 2036 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
protected |
In RGB-D TUM Datasets update the Intensity image displayed in a seperate viewport.
Definition at line 1239 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
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 1825 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, mrpt::maps::CMetricMap::insertObservation(), MRPT_END, MRPT_LOG_DEBUG_STREAM, MRPT_START, mrpt::system::CTicTac::Tac(), and mrpt::system::CTicTac::Tic().
|
protected |
Update odometry-only cloud with latest odometry estimation.
Definition at line 2111 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, ASSERTDEBMSG_, MRPT_END, and MRPT_START.
|
protected |
In RGB-D TUM Datasets update the Range image displayed in a seperate viewport.
Definition at line 1189 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, MRPT_START, and mrpt::img::CImage::setFromMatrix().
|
protected |
Update the displayPlots window with the new information with regards to the metric.
Definition at line 2522 of file CGraphSlamEngine_impl.h.
References ASSERTDEB_, MRPT_END, and MRPT_START.
|
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 165 of file COutputLogger.cpp.
References ASSERTMSG_, and mrpt::format().
|
staticprotected |
Separator string to be used in debugging messages.
Definition at line 969 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 240 of file system/COutputLogger.h.
|
inherited |
[Default=false] Enables storing all messages into an internal list.
Definition at line 243 of file system/COutputLogger.h.
|
protected |
Definition at line 952 of file CGraphSlamEngine.h.
|
protected |
Definition at line 713 of file CGraphSlamEngine.h.
|
protected |
Definition at line 883 of file CGraphSlamEngine.h.
|
protected |
Current robot position based solely on odometry.
Definition at line 925 of file CGraphSlamEngine.h.
|
protected |
Current dataset timestamp.
Definition at line 923 of file CGraphSlamEngine.h.
|
protected |
Type of constraint currently in use.
Definition at line 965 of file CGraphSlamEngine.h.
|
protected |
Definition at line 852 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 918 of file CGraphSlamEngine.h.
|
protected |
Definition at line 884 of file CGraphSlamEngine.h.
|
protected |
Instance to keep track of all the edges + visualization related operations.
Definition at line 818 of file CGraphSlamEngine.h.
|
protected |
Definition at line 706 of file CGraphSlamEngine.h.
|
protected |
Definition at line 763 of file CGraphSlamEngine.h.
|
protected |
Definition at line 764 of file CGraphSlamEngine.h.
|
protected |
Definition at line 765 of file CGraphSlamEngine.h.
|
protected |
Determine if we are to enable visualization support or not.
Definition at line 711 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().
|
protected |
Definition at line 850 of file CGraphSlamEngine.h.
|
protected |
First recorded laser scan - assigned to the root.
Definition at line 841 of file CGraphSlamEngine.h.
|
protected |
Definition at line 721 of file CGraphSlamEngine.h.
|
protected |
The graph object to be built and optimized.
Definition at line 699 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getGraph().
|
mutableprotected |
Mark graph modification/accessing explicitly for multithreaded implementation.
Definition at line 869 of file CGraphSlamEngine.h.
|
mutableprotected |
Definition at line 936 of file CGraphSlamEngine.h.
|
protected |
Definition at line 849 of file CGraphSlamEngine.h.
|
protected |
Definition at line 832 of file CGraphSlamEngine.h.
|
protected |
Definition at line 830 of file CGraphSlamEngine.h.
|
protected |
Counter for reading back the GT_poses.
Definition at line 724 of file CGraphSlamEngine.h.
|
protected |
Rate at which to read the GT poses.
Definition at line 726 of file CGraphSlamEngine.h.
|
protected |
Definition at line 730 of file CGraphSlamEngine.h.
|
protected |
Definition at line 873 of file CGraphSlamEngine.h.
|
protected |
Definition at line 874 of file CGraphSlamEngine.h.
|
protected |
|
protected |
First recorded timestamp in the dataset.
Definition at line 921 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 957 of file CGraphSlamEngine.h.
|
mutableprotected |
Indicated if program is temporarily paused by the user.
Definition at line 770 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::isPaused(), mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().
|
protected |
Definition at line 811 of file CGraphSlamEngine.h.
|
protected |
Definition at line 810 of file CGraphSlamEngine.h.
|
protected |
Definition at line 812 of file CGraphSlamEngine.h.
|
protected |
Definition at line 809 of file CGraphSlamEngine.h.
|
protected |
Definition at line 808 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec().
|
protected |
Last laser scan that the current class instance received.
Definition at line 839 of file CGraphSlamEngine.h.
|
protected |
Last laser scan that the current class instance received.
Definition at line 844 of file CGraphSlamEngine.h.
|
mutableprotected |
Timestamp at which the map was computed.
Definition at line 949 of file CGraphSlamEngine.h.
|
mutableprotected |
Indicates if the map is cached.
Definition at line 944 of file CGraphSlamEngine.h.
|
protectedinherited |
Provided messages with VerbosityLevel smaller than this value shall be ignored.
Definition at line 253 of file system/COutputLogger.h.
Referenced by mrpt::system::COutputLogger::getMinLoggingLevel(), and mrpt::system::COutputLogger::isLoggingLevelVisible().
|
protected |
Definition at line 705 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 865 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 882 of file CGraphSlamEngine.h.
|
protected |
Map of NodeIDs to their corresponding LaserScans.
Definition at line 836 of file CGraphSlamEngine.h.
|
protected |
Definition at line 731 of file CGraphSlamEngine.h.
|
mutableprotected |
Definition at line 939 of file CGraphSlamEngine.h.
|
protected |
Definition at line 848 of file CGraphSlamEngine.h.
|
protected |
Definition at line 829 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 786 of file CGraphSlamEngine.h.
|
protected |
Definition at line 792 of file CGraphSlamEngine.h.
|
protected |
Definition at line 790 of file CGraphSlamEngine.h.
|
protected |
Definition at line 789 of file CGraphSlamEngine.h.
|
protected |
Definition at line 788 of file CGraphSlamEngine.h.
|
protected |
Definition at line 793 of file CGraphSlamEngine.h.
|
protected |
Definition at line 791 of file CGraphSlamEngine.h.
|
protected |
Definition at line 851 of file CGraphSlamEngine.h.
|
protected |
Definition at line 707 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 736 of file CGraphSlamEngine.h.
|
protected |
Message to be displayed while paused.
Definition at line 773 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec().
|
protected |
Rawlog file from which to read the measurements.
If string is empty, process is to be run online
Definition at line 719 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::getRawlogFname().
|
protected |
Indicate whether the user wants to exit the application (e.g.
pressed by pressign ctrl-c)
Definition at line 930 of file CGraphSlamEngine.h.
|
protected |
How big are the robots going to be in the scene.
Definition at line 860 of file CGraphSlamEngine.h.
|
protected |
Definition at line 858 of file CGraphSlamEngine.h.
|
mutableprotected |
Acquired map in CSimpleMap representation.
Definition at line 938 of file CGraphSlamEngine.h.
|
protected |
MRPT CNetworkOfPoses constraint classes that are currently supported.
Definition at line 962 of file CGraphSlamEngine.h.
|
protected |
Definition at line 799 of file CGraphSlamEngine.h.
|
protected |
Definition at line 797 of file CGraphSlamEngine.h.
|
protected |
Definition at line 796 of file CGraphSlamEngine.h.
|
protected |
Definition at line 795 of file CGraphSlamEngine.h.
|
protected |
Definition at line 800 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().
|
protected |
Definition at line 798 of file CGraphSlamEngine.h.
|
protected |
Time logger instance.
Definition at line 696 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 826 of file CGraphSlamEngine.h.
|
protected |
Definition at line 728 of file CGraphSlamEngine.h.
|
protected |
Definition at line 761 of file CGraphSlamEngine.h.
|
protected |
Definition at line 759 of file CGraphSlamEngine.h.
|
protected |
Definition at line 760 of file CGraphSlamEngine.h.
|
protected |
Definition at line 758 of file CGraphSlamEngine.h.
|
protected |
Definition at line 762 of file CGraphSlamEngine.h.
|
protected |
Definition at line 741 of file CGraphSlamEngine.h.
Referenced by mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::pauseExec(), and mrpt::graphslam::CGraphSlamEngine< GRAPH_T >::resumeExec().
|
protected |
Definition at line 740 of file CGraphSlamEngine.h.
|
protected |
Definition at line 742 of file CGraphSlamEngine.h.
|
protected |
DisplayPlots instance for visualizing the evolution of the SLAM metric.
Definition at line 746 of file CGraphSlamEngine.h.
|
staticprotected |
Definition at line 970 of file CGraphSlamEngine.h.
Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020 |