10 #ifndef GRAPHSLAMENGINE_H 11 #define GRAPHSLAMENGINE_H 81 namespace mrpt {
namespace graphslam {
190 template<
class GRAPH_T=
typename mrpt::graphs::CNetworkOfPoses2DInf>
197 typedef std::map<std::string, mrpt::utils::CFileOutputStream*>
fstreams_out;
204 typedef typename GRAPH_T::constraint_t::type_value
pose_t;
261 typename GRAPH_T::global_poses_t* graph_poses)
const;
266 std::set<mrpt::utils::TNodeID>* nodes_set)
const;
317 void getMap(mrpt::maps::COccupancyGridMap2DPtr map,
319 void getMap(mrpt::maps::COctoMapPtr map,
342 mrpt::obs::CObservationPtr& observation,
343 size_t& rawlog_entry);
355 mrpt::obs::CActionCollectionPtr& action,
356 mrpt::obs::CSensoryFramePtr& observations,
357 mrpt::obs::CObservationPtr& observation,
358 size_t& rawlog_entry);
387 std::vector<mrpt::poses::CPose2D>* gt_poses,
388 std::vector<mrpt::system::TTimeStamp>* gt_timestamps=NULL);
391 std::vector<mrpt::poses::CPose3D>* gt_poses,
392 std::vector<mrpt::system::TTimeStamp>* gt_timestamps=NULL);
413 std::vector<mrpt::poses::CPose2D>* gt_poses,
414 std::vector<mrpt::system::TTimeStamp>* gt_timestamps=NULL);
438 std::map<std::string, int>* node_stats,
439 std::map<std::string, int>* edge_stats,
474 "\" in the dipslay window to resume");
585 mrpt::opengl::CSetOfObjectsPtr& viz_object);
598 mrpt::obs::CObservation2DRangeScanPtr>& nodes_to_laser_scans2D,
599 bool full_update=
false);
647 const int keep_every_n_entries = 2);
673 int sleep_time=500 );
689 const mrpt::obs::CActionCollectionPtr action,
690 const mrpt::obs::CSensoryFramePtr observations,
691 const mrpt::obs::CObservationPtr observation);
721 const size_t model_size=1,
733 bool registered=
false,
951 std::map<std::string, std::string>
fields;
void updateOdometryVisualization()
Update odometry-only cloud with latest odometry estimation.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
std::map< mrpt::utils::TNodeID, size_t > m_nodeID_to_gt_indices
Map from nodeIDs to their corresponding closest GT pose index.
double m_offset_y_paused_message
This class provides simple critical sections functionality.
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.
mrpt::obs::CObservation2DRangeScanPtr m_first_laser_scan2D
First recorded laser scan - assigned to the root.
int m_text_index_timestamp
void queryObserverForEvents()
Query the observer instance for any user events.
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_T > * m_edge_reg
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
mrpt::gui::CDisplayWindow3D * m_win
void save3DScene(const std::string *fname_in=NULL) const
Wrapper method around the COpenGLScene::saveToFile method.
bool m_enable_curr_pos_viewport
void updateGTVisualization()
Display the next ground truth position in the visualization window.
Create a GUI window and display plots with MATLAB-like interfaces and commands.
void computeMap() const
Compute the map of the environment based on the recorded measurements.
void toggleMapVisualization()
void computeSlamMetric(mrpt::utils::TNodeID nodeID, size_t gt_index)
Compare the SLAM result (estimated trajectory) with the GT path.
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
virtual void getNodeIDsOfEstimatedTrajectory(std::set< mrpt::utils::TNodeID > *nodes_set) const
Return the list of nodeIDs which make up robot trajectory.
void updateSlamMetricVisualization()
Update the displayPlots window with the new information with regards to the metric.
double m_offset_y_timestamp
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.
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.
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.
std::map< std::string, mrpt::utils::CFileOutputStream * > fstreams_out
Handy typedefs.
mrpt::maps::CSimpleMap m_simple_map_cached
Acquired map in CSimpleMap representation.
bool execGraphSlamStep(mrpt::obs::CObservationPtr &observation, size_t &rawlog_entry)
Wrapper method around _execGraphSlamStep.
mrpt::gui::CDisplayWindowPlots * m_win_plot
DisplayPlots instance for visualizing the evolution of the SLAM metric.
global_pose_t getCurrentRobotPosEstimation() const
Query CGraphSlamEngine instance for the current estimated robot position.
void initRangeImageViewport()
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::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.
void initGTVisualization()
mrpt::math::CMatrixDouble33 m_rot_TUM_to_MRPT
mrpt::utils::CTimeLogger m_time_logger
Time logger instance.
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.
mrpt::utils::TNodeID m_nodeID_max
Internal counter for querying for the number of nodeIDs.
std::string m_rawlog_fname
Rawlog file from which to read the measurements.
virtual void getRobotEstimatedTrajectory(typename GRAPH_T::global_poses_t *graph_poses) const
void updateAllVisuals()
Wrapper around the deciders/optimizer updateVisuals methods.
GRAPH_T::constraint_t constraint_t
Type of graph constraints.
bool m_observation_only_dataset
static double accumulateAngleDiffs(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
static const std::string report_sep
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...
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...
uint64_t TNodeID
The type for node IDs in graphs of different types.
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.
void BASE_IMPEXP sleep(int time_ms) MRPT_NO_THROWS
An OS-independent method for sending the current thread to "sleep" for a given period of time...
struct mrpt::graphslam::CGraphSlamEngine::TRGBDInfoFileParams m_info_params
mrpt::obs::CObservation3DRangeScanPtr m_last_laser_scan3D
Last laser scan that the current class instance received.
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.
mrpt::utils::TColor m_GT_color
std::map< std::string, std::string > fields
Format for the parameters in the info file: string literal - related value (kept in a string represen...
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...
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.
mrpt::graphslam::CWindowObserver * m_win_observer
#define MRPT_LOG_WARN_STREAM(__CONTENTS)
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()
const GRAPH_T & getGraph() const
Return a reference to the underlying GRAPH_T instance.
GLsizei const GLchar ** string
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal(const mrpt::poses::CPose2D &p_unused)
Method to help overcome the partial template specialization restriction of C++.
virtual ~CGraphSlamEngine()
Default Destructor.
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.
mrpt::utils::TColor m_estimated_traj_color
void toggleEstimatedTrajectoryVisualization()
std::map< std::string, mrpt::utils::CFileOutputStream * >::iterator fstreams_out_it
Map for iterating over output file streams.
void initIntensityImageViewport()
std::vector< double > m_deformation_energy_vec
void toggleOdometryVisualization()
void saveGraph(const std::string *fname_in=NULL) const
Wrapper method around the GRAPH_T::saveToTextFile method.
std::string m_img_external_storage_dir
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualization()
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.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::maps::COccupancyGridMap2DPtr m_gridmap_cached
GRAPH_T::global_pose_t global_pose_t
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
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.
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.
#define MRPT_LOG_INFO_STREAM(__CONTENTS)
int m_text_index_estimated_traj
bool m_enable_intensity_viewport
double m_offset_y_odometry
std::string m_GT_file_format
mrpt::synch::CCriticalSection m_graph_section
Mark graph modification/accessing explicitly for multithreaded implementation.
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::system::TTimeStamp m_curr_timestamp
Current dataset timestamp.
std::string BASE_IMPEXP 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
A RGB color - floats in the range [0,1].
A versatile "profiler" that logs the time spent within each pair of calls to enter(X)-leave(X), among other stats.
bool m_visualize_odometry_poses
const std::string m_paused_message
Message to be displayed while paused.
mrpt::utils::TColor m_odometry_color
std::string m_keystroke_odometry
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization(const mrpt::utils::TNodeID nodeID) const
return the 3D Pose of a LaserScan that is to be visualized.
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()
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.
mrpt::maps::COctoMapPtr m_octomap_cached
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 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. ...
mrpt::utils::TColor m_optimized_map_color
mrpt::obs::CObservation2DRangeScanPtr m_last_laser_scan2D
Last laser scan that the current class instance received.
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()
std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > nodes_to_scans2D_t
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.
bool m_map_is_cached
Indicates if the map is cached.
void initSlamMetricVisualization()
mrpt::utils::TColor m_current_constraint_type_color
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.
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
void addTextMessage(const double x, const double y, const std::string &text, const mrpt::utils::TColorf &color=mrpt::utils::TColorf(1.0, 1.0, 1.0), const size_t unique_index=0, const mrpt::opengl::TOpenGLFont font=mrpt::opengl::MRPT_GLUT_BITMAP_TIMES_ROMAN_24)
Add 2D text messages overlapped to the 3D rendered scene.
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::COccupancyGridMap2DPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
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