Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t > Class Template Reference

Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS. More...

#include <CGraphSlamEngine_ROS.h>

Inheritance diagram for mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >:
Inheritance graph
[legend]

Public Types

typedef CGraphSlamEngine< GRAPH_t > parent
 
- Public Types inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
typedef GRAPH_t::constraint_t constraint_t
 
typedef GRAPH_t::constraint_t constraint_t
 
typedef std::map< std::string, mrpt::utils::CFileOutputStream * > fstreams_out
 
typedef std::map< std::string, mrpt::utils::CFileOutputStream * > fstreams_out
 
typedef std::map< std::string, mrpt::utils::CFileOutputStream * >::iterator fstreams_out_it
 
typedef std::map< std::string, mrpt::utils::CFileOutputStream * >::iterator fstreams_out_it
 
typedef GRAPH_t::global_pose_t global_pose_t
 
typedef GRAPH_t::global_pose_t global_pose_t
 
typedef std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > nodes_to_scans2D_t
 
typedef std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > nodes_to_scans2D_t
 
typedef GRAPH_t::constraint_t::type_value pose_t
 
typedef GRAPH_t::constraint_t::type_value pose_t
 

Public Member Functions

 CGraphSlamEngine_ROS (ros::NodeHandle *nh, 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)
 
void initClass ()
 Initialize object instance. More...
 
void setupComm ()
 Wrapper method around the protected setup* class methods. More...
 
virtual ~CGraphSlamEngine_ROS ()
 
- Public Member Functions inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
virtual bool _execGraphSlamStep (mrpt::obs::CActionCollectionPtr &action, mrpt::obs::CSensoryFramePtr &observations, mrpt::obs::CObservationPtr &observation, size_t &rawlog_entry)
 
 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)
 
void computeMap () const
 
void computeMap () const
 
bool execGraphSlamStep (mrpt::obs::CObservationPtr &observation, size_t &rawlog_entry)
 
void generateReportFiles (const std::string &output_dir_fname_in)
 
global_pose_t getCurrentRobotPosEstimation () const
 
void getDeformationEnergyVector (std::vector< double > *vec_out) const
 
const GRAPH_t & getGraph () const
 
bool getGraphSlamStats (std::map< std::string, int > *node_stats, std::map< std::string, int > *edge_stats, mrpt::system::TTimeStamp *timestamp=NULL)
 
void getMap (mrpt::maps::COccupancyGridMap2DPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
 
void getMap (mrpt::maps::COctoMapPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
 
void getMap (mrpt::maps::COccupancyGridMap2DPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
 
void getMap (mrpt::maps::COctoMapPtr map, mrpt::system::TTimeStamp *acquisition_time=NULL) const
 
virtual void getNodeIDsOfEstimatedTrajectory (std::set< mrpt::utils::TNodeID > *nodes_set) const
 
void getParamsAsString (std::string *params_out) const
 
std::string getParamsAsString () const
 
std::string getRawlogFname ()
 
virtual void getRobotEstimatedTrajectory (typename GRAPH_t::global_poses_t *graph_poses) const
 
bool isPaused () const
 
bool isPaused () const
 
void loadParams (const std::string &fname)
 
void pauseExec ()
 
void pauseExec ()
 
void printParams () const
 
void resumeExec () const
 
void resumeExec () const
 
void save3DScene (const std::string *fname_in=NULL) const
 
void saveGraph (const std::string *fname_in=NULL) const
 
void togglePause ()
 
void togglePause ()
 
virtual ~CGraphSlamEngine ()
 

Public Attributes

ros::NodeHandlem_nh
 

Protected Member Functions

virtual bool _execGraphSlamStep (mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &observations, mrpt::obs::CObservation::Ptr &observation, size_t &rawlog_entry)
 
void readParams ()
 Read the problem configuration parameters. More...
 
void readROSParameters ()
 Read configuration parameters from the ROS parameter server. More...
 
virtual void usePublishersBroadcasters ()
 Provide feedback about the SLAM operation. More...
 
setup* ROS-related methods

Methods for setting up topic subscribers, publishers, and corresponding services

See also
setupComm
virtual void setupSubs ()
 
virtual void setupPubs ()
 
virtual void setupSrvs ()
 
- Protected Member Functions inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
void alignOpticalWithMRPTFrame ()
 
void computeSlamMetric (mrpt::utils::TNodeID nodeID, size_t gt_index)
 
void decimateLaserScan (mrpt::obs::CObservation2DRangeScan &laser_scan_in, mrpt::obs::CObservation2DRangeScan *laser_scan_out, const int keep_every_n_entries=2)
 
void dumpVisibilityErrorMsg (std::string viz_flag, int sleep_time=500)
 
void execDijkstraNodesEstimation ()
 
void getDescriptiveReport (std::string *report_str) const
 
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization (const mrpt::utils::TNodeID nodeID) const
 
virtual mrpt::poses::CPose3D getLSPoseForGridMapVisualization (const mrpt::utils::TNodeID nodeID) const
 
void initClass ()
 
void initCurrPosViewport ()
 
void initEstimatedTrajectoryVisualization ()
 
void initGTVisualization ()
 
void initIntensityImageViewport ()
 
void initIntensityImageViewport ()
 
void initMapVisualization ()
 
void initMapVisualization ()
 
void initOdometryVisualization ()
 
void initRangeImageViewport ()
 
void initRangeImageViewport ()
 
void initResultsFile (const std::string &fname)
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualization ()
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualization ()
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal (const mrpt::poses::CPose2D &p_unused)
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal (const mrpt::poses::CPose3D &p_unused)
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal (const mrpt::poses::CPose2D &p_unused)
 
mrpt::opengl::CSetOfObjectsPtr initRobotModelVisualizationInternal (const mrpt::poses::CPose3D &p_unused)
 
void initSlamMetricVisualization ()
 
void initVisualization ()
 
void initVisualization ()
 
virtual void monitorNodeRegistration (bool registered=false, std::string class_name="Class")
 
void queryObserverForEvents ()
 
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())
 
virtual void setObjectPropsFromNodeID (const mrpt::utils::TNodeID nodeID, mrpt::opengl::CSetOfObjectsPtr &viz_object)
 
virtual void setObjectPropsFromNodeID (const mrpt::utils::TNodeID nodeID, mrpt::opengl::CSetOfObjectsPtr &viz_object)
 
void toggleEstimatedTrajectoryVisualization ()
 
void toggleEstimatedTrajectoryVisualization ()
 
void toggleGTVisualization ()
 
void toggleGTVisualization ()
 
void toggleMapVisualization ()
 
void toggleMapVisualization ()
 
void toggleOdometryVisualization ()
 
void toggleOdometryVisualization ()
 
void updateAllVisuals ()
 
void updateAllVisuals ()
 
virtual void updateCurrPosViewport ()
 
virtual void updateCurrPosViewport ()
 
void updateEstimatedTrajectoryVisualization (bool full_update=false)
 
void updateEstimatedTrajectoryVisualization (bool full_update=false)
 
void updateGTVisualization ()
 
void updateGTVisualization ()
 
void updateIntensityImageViewport ()
 
void updateIntensityImageViewport ()
 
void updateMapVisualization (const std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > &nodes_to_laser_scans2D, bool full_update=false)
 
void updateMapVisualization (const std::map< mrpt::utils::TNodeID, mrpt::obs::CObservation2DRangeScanPtr > &nodes_to_laser_scans2D, bool full_update=false)
 
void updateOdometryVisualization ()
 
void updateOdometryVisualization ()
 
void updateRangeImageViewport ()
 
void updateRangeImageViewport ()
 
void updateSlamMetricVisualization ()
 
void updateSlamMetricVisualization ()
 

Protected Attributes

ros::CallbackQueue custom_service_queue
 Custom Callback queue for processing requests for the services outside the standard CallbackQueue. More...
 
int m_queue_size
 
- Protected Attributes inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
std::string m_class_name
 
std::string m_config_fname
 
double m_curr_deformation_energy
 
pose_t m_curr_odometry_only_pose
 
mrpt::system::TTimeStamp m_curr_timestamp
 
std::string m_current_constraint_type
 
mrpt::utils::TColor m_current_constraint_type_color
 
double m_dataset_grab_time
 
std::vector< double > m_deformation_energy_vec
 
mrpt::graphslam::detail::CEdgeCounter m_edge_counter
 
mrpt::graphslam::deciders::CEdgeRegistrationDecider< GRAPH_t > * m_edge_reg
 
bool m_enable_curr_pos_viewport
 
bool m_enable_intensity_viewport
 
bool m_enable_range_viewport
 
const bool m_enable_visuals
 
mrpt::utils::TColor m_estimated_traj_color
 
mrpt::obs::CObservation2DRangeScanPtr m_first_laser_scan2D
 
std::string m_fname_GT
 
GRAPH_t m_graph
 
mrpt::synch::CCriticalSection m_graph_section
 
mrpt::maps::COccupancyGridMap2DPtr m_gridmap_cached
 
mrpt::utils::TColor m_GT_color
 
std::string m_GT_file_format
 
std::vector< pose_tm_GT_poses
 
size_t m_GT_poses_index
 
size_t m_GT_poses_step
 
bool m_has_read_config
 
std::string m_img_external_storage_dir
 
std::string m_img_prev_path_base
 
struct mrpt::graphslam::CGraphSlamEngine::TRGBDInfoFileParams m_info_params
 
mrpt::system::TTimeStamp m_init_timestamp
 
bool m_is_first_time_node_reg
 
bool m_is_paused
 
std::string m_keystroke_estimated_trajectory
 
std::string m_keystroke_GT
 
std::string m_keystroke_map
 
std::string m_keystroke_odometry
 
std::string m_keystroke_pause_exec
 
mrpt::obs::CObservation2DRangeScanPtr m_last_laser_scan2D
 
mrpt::obs::CObservation3DRangeScanPtr m_last_laser_scan3D
 
mrpt::system::TTimeStamp m_map_acq_time
 
bool m_map_is_cached
 
mrpt::graphslam::deciders::CNodeRegistrationDecider< GRAPH_t > * m_node_reg
 
mrpt::utils::TNodeID m_nodeID_max
 
std::map< mrpt::utils::TNodeID, size_t > m_nodeID_to_gt_indices
 
nodes_to_scans2D_t m_nodes_to_laser_scans2D
 
bool m_observation_only_dataset
 
mrpt::maps::COctoMapPtr m_octomap_cached
 
mrpt::utils::TColor m_odometry_color
 
std::vector< pose_tm_odometry_poses
 
double m_offset_x_left
 
double m_offset_y_current_constraint_type
 
double m_offset_y_estimated_traj
 
double m_offset_y_GT
 
double m_offset_y_odometry
 
double m_offset_y_paused_message
 
double m_offset_y_timestamp
 
mrpt::utils::TColor m_optimized_map_color
 
mrpt::graphslam::optimizers::CGraphSlamOptimizer< GRAPH_t > * m_optimizer
 
fstreams_out m_out_streams
 
const std::string m_paused_message
 
std::string m_rawlog_fname
 
bool m_request_to_exit
 
size_t m_robot_model_size
 
mrpt::math::CMatrixDouble33 m_rot_TUM_to_MRPT
 
mrpt::maps::CSimpleMap m_simple_map_cached
 
std::vector< std::stringm_supported_constraint_types
 
int m_text_index_current_constraint_type
 
int m_text_index_estimated_traj
 
int m_text_index_GT
 
int m_text_index_odometry
 
int m_text_index_paused_message
 
int m_text_index_timestamp
 
mrpt::utils::CTimeLogger m_time_logger
 
bool m_use_GT
 
bool m_user_decides_about_output_dir
 
bool m_visualize_estimated_trajectory
 
bool m_visualize_GT
 
bool m_visualize_map
 
bool m_visualize_odometry_poses
 
bool m_visualize_SLAM_metric
 
mrpt::gui::CDisplayWindow3Dm_win
 
mrpt::graphslam::CWindowManagerm_win_manager
 
mrpt::graphslam::CWindowObserverm_win_observer
 
mrpt::gui::CDisplayWindowPlotsm_win_plot
 

Additional Inherited Members

- Static Public Member Functions inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
static void readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
static void readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose3D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
static void readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose3D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
static void readGTFile (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
static void readGTFileRGBD_TUM (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
static void readGTFileRGBD_TUM (const std::string &fname_GT, std::vector< mrpt::poses::CPose2D > *gt_poses, std::vector< mrpt::system::TTimeStamp > *gt_timestamps=NULL)
 
- Static Protected Member Functions inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
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)
 
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)
 
static mrpt::system::TTimeStamp getTimeStamp (const mrpt::obs::CActionCollectionPtr action, const mrpt::obs::CSensoryFramePtr observations, const mrpt::obs::CObservationPtr observation)
 
- Static Protected Attributes inherited from mrpt::graphslam::CGraphSlamEngine< GRAPH_t >
static const std::string header_sep
 
static const std::string report_sep
 

Detailed Description

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
class mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >

Class template that provides a wrapper around the MRPT CGraphSlamEngine class template and implements methods for interacting with ROS.

Definition at line 25 of file CGraphSlamEngine_ROS.h.

Member Typedef Documentation

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
typedef CGraphSlamEngine<GRAPH_t> mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::parent

Definition at line 28 of file CGraphSlamEngine_ROS.h.

Constructor & Destructor Documentation

template<class GRAPH_t>
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::CGraphSlamEngine_ROS ( ros::NodeHandle nh,
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 
)

Definition at line 14 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::~CGraphSlamEngine_ROS ( )
virtual

Definition at line 37 of file CGraphSlamEngine_ROS_impl.h.

Member Function Documentation

template<class GRAPH_t >
bool mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::_execGraphSlamStep ( mrpt::obs::CActionCollection::Ptr &  action,
mrpt::obs::CSensoryFrame::Ptr &  observations,
mrpt::obs::CObservation::Ptr &  observation,
size_t &  rawlog_entry 
)
protectedvirtual
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::initClass ( )

Initialize object instance.

Definition at line 43 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readParams ( )
protected

Read the problem configuration parameters.

See also
readROSParameters, CGraphSlamEngine::loadParams

Definition at line 82 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::readROSParameters ( )
protected

Read configuration parameters from the ROS parameter server.

Note
Method is automatically called on object construction.
See also
readParams, initClass

Definition at line 88 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupComm ( )

Wrapper method around the protected setup* class methods.

Handy for setting up publishers, subscribers, services all at once.

Definition at line 108 of file CGraphSlamEngine_ROS_impl.h.

template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupPubs ( )
protectedvirtual
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSrvs ( )
protectedvirtual
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::setupSubs ( )
protectedvirtual
template<class GRAPH_t >
void mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::usePublishersBroadcasters ( )
protectedvirtual

Provide feedback about the SLAM operation.

Method makes the necessary calls to all the publishers of the class and broadcaster instances

Reimplemented in mrpt::graphslam::CGraphSlamEngine_MR< GRAPH_T >.

Definition at line 105 of file CGraphSlamEngine_ROS_impl.h.

Member Data Documentation

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
ros::CallbackQueue mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::custom_service_queue
protected

Custom Callback queue for processing requests for the services outside the standard CallbackQueue.

Note
Logical thing would be to define it in CGraphSlamEngine_MR, but that results in an segfault with the following error message:
pure virtual method called
terminate called without an active exception

Definition at line 97 of file CGraphSlamEngine_ROS.h.

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
ros::NodeHandle* mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_nh

Definition at line 51 of file CGraphSlamEngine_ROS.h.

template<class GRAPH_t = typename mrpt::graphs::CNetworkOfPoses2DInf>
int mrpt::graphslam::CGraphSlamEngine_ROS< GRAPH_t >::m_queue_size
protected

Definition at line 100 of file CGraphSlamEngine_ROS.h.


The documentation for this class was generated from the following files:


mrpt_graphslam_2d
Author(s): Nikos Koukis
autogenerated on Sat May 2 2020 03:44:17